19#include <rclcpp/rclcpp.hpp>
21#include <carma_planning_msgs/msg/trajectory_plan_point.hpp>
22#include <geometry_msgs/msg/twist_stamped.hpp>
23#include <autoware_msgs/msg/control_command.hpp>
24#include <carma_planning_msgs/msg/platooning_info.hpp>
29#include <pure_pursuit/pure_pursuit.hpp>
31#include <gtest/gtest_prod.h>
33namespace pure_pursuit = autoware::motion::control::pure_pursuit;
55 autoware_msgs::msg::ControlCommandStamped
generate_control_signals(
const carma_planning_msgs::msg::TrajectoryPlanPoint& first_trajectory_point,
const geometry_msgs::msg::PoseStamped& current_pose,
const geometry_msgs::msg::TwistStamped& current_twist);
63 geometry_msgs::msg::TwistStamped
compose_twist_cmd(
double linear_vel,
double angular_vel);
65 motion::motion_common::State
convert_state(
const geometry_msgs::msg::PoseStamped& pose,
const geometry_msgs::msg::TwistStamped& twist)
const;
86 autoware_msgs::msg::ControlCommandStamped
compose_ctrl_cmd(
double linear_vel,
double steering_angle);
109 std::shared_ptr<pure_pursuit::PurePursuit>
pp_;
129 void platoon_info_cb(
const carma_planning_msgs::msg::PlatooningInfo::SharedPtr msg);
136 double get_trajectory_speed(
const std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint>& trajectory_points);
148 FRIEND_TEST(PlatooningControlPluginTest, test_get_trajectory_speed);
150 FRIEND_TEST(PlatooningControlPluginTest, test_current_trajectory_callback);
ControlPlugin base class which can be extended by user provided plugins which wish to implement the C...
This class includes node-level logic for Platooning Control such as its publishers,...
motion::motion_common::State convert_state(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::TwistStamped &twist) const
void platoon_info_cb(const carma_planning_msgs::msg::PlatooningInfo::SharedPtr msg)
callback function for platoon info
bool get_availability() override
Returns availability of plugin. Always true.
carma_ros2_utils::CallbackReturn on_configure_plugin() override
This method should be used to load parameters and will be called on the configure state transition.
void current_trajectory_callback(const carma_planning_msgs::msg::TrajectoryPlan::UniquePtr tp)
callback function for trajectory plan
double prev_input_time_ms_
double get_trajectory_speed(const std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &trajectory_points)
calculate average speed of a set of trajectory points
geometry_msgs::msg::TwistStamped compose_twist_cmd(double linear_vel, double angular_vel)
Compose twist message from linear and angular velocity commands.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Callback for dynamic parameter updates.
FRIEND_TEST(PlatooningControlPluginTest, test_get_trajectory_speed)
std::string get_version_id() override
Returns version id of plugn.
PlatooningControlWorker pcw_
autoware_msgs::msg::ControlCommandStamped compose_ctrl_cmd(double linear_vel, double steering_angle)
Compose control message from speed and steering commands.
PlatoonLeaderInfo platoon_leader_
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::PlatooningInfo > platoon_info_sub_
FRIEND_TEST(PlatooningControlPluginTest, test_generate_controls)
FRIEND_TEST(PlatooningControlPluginTest, test_platoon_info_cb)
FRIEND_TEST(PlatooningControlPluginTest, test_current_trajectory_callback)
autoware_msgs::msg::ControlCommandStamped generate_control_signals(const carma_planning_msgs::msg::TrajectoryPlanPoint &first_trajectory_point, const geometry_msgs::msg::PoseStamped ¤t_pose, const geometry_msgs::msg::TwistStamped ¤t_twist)
generate control signal by calculating speed and steering commands.
autoware_msgs::msg::ControlCommandStamped generate_command() override
Extending class provided method which should generate a command message which will be published to th...
long consecutive_input_counter_
std::shared_ptr< pure_pursuit::PurePursuit > pp_
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::PlatooningInfo > platoon_info_pub_
PlatooningControlPluginConfig config_
PlatooningControlPlugin(const rclcpp::NodeOptions &options)
PlatooningControlPlugin constructor.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::TrajectoryPlan > trajectory_plan_sub_
This is the worker class for platoon controller. It is responsible for generating and smoothing the s...
Stuct containing the algorithm configuration values for the PlatooningControlPlugin.