19#include <rclcpp/rclcpp.hpp>
20#include <carma_planning_msgs/msg/trajectory_plan.hpp>
22#include <autoware_auto_msgs/msg/vehicle_kinematic_state.hpp>
23#include <autoware_auto_msgs/msg/vehicle_control_command.hpp>
24#include <autoware_auto_msgs/msg/trajectory.hpp>
25#include <autoware_auto_msgs/msg/ackermann_control_command.hpp>
26#include <gtest/gtest_prod.h>
42 carma_ros2_utils::SubPtr<autoware_auto_msgs::msg::AckermannControlCommand>
control_cmd_sub_;
64 rcl_interfaces::msg::SetParametersResult
75 void ackermann_control_cb(
const autoware_auto_msgs::msg::AckermannControlCommand::SharedPtr msg);
80 bool isControlCommandOld(
const autoware_auto_msgs::msg::AckermannControlCommand& cmd)
const;
90 autoware_auto_msgs::msg::VehicleKinematicState
convert_state(
const geometry_msgs::msg::PoseStamped& pose,
const geometry_msgs::msg::TwistStamped& twist)
const;
95 autoware_msgs::msg::ControlCommandStamped
convert_cmd(
const autoware_auto_msgs::msg::AckermannControlCommand& cmd)
const;
ControlPlugin base class which can be extended by user provided plugins which wish to implement the C...
bool isControlCommandOld(const autoware_auto_msgs::msg::AckermannControlCommand &cmd) const
Check to see if the received control command recent or old.
rclcpp::TimerBase::SharedPtr autoware_info_timer_
autoware_msgs::msg::ControlCommandStamped convert_cmd(const autoware_auto_msgs::msg::AckermannControlCommand &cmd) const
convert autoware Ackermann control command to autoware stamped control command
carma_ros2_utils::PubPtr< autoware_auto_msgs::msg::Trajectory > autoware_traj_pub_
carma_ros2_utils::PubPtr< autoware_auto_msgs::msg::VehicleKinematicState > autoware_state_pub_
double get_wheel_angle_rad_from_twist(const geometry_msgs::msg::TwistStamped &twist) const
calculate wheel angle in rad from angular velocity in twist message
carma_ros2_utils::SubPtr< autoware_auto_msgs::msg::AckermannControlCommand > control_cmd_sub_
void ackermann_control_cb(const autoware_auto_msgs::msg::AckermannControlCommand::SharedPtr msg)
autoware's control subscription callback
void autoware_info_timer_callback()
Timer callback to spin at 30 hz and frequently publish autoware kinematic state and trajectory.
TrajectoryFollowerWrapperNode(const rclcpp::NodeOptions &options)
Node constructor.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Callback for dynamic parameter updates.
autoware_auto_msgs::msg::VehicleKinematicState convert_state(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::TwistStamped &twist) const
convert vehicle's pose and twist messages to autoware kinematic state
FRIEND_TEST(TesttrajectoryFollowerWrapper, TestThreshold)
FRIEND_TEST(TesttrajectoryFollowerWrapper, TestControlCallback)
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
TrajectoryFollowerWrapperConfig config_
std::optional< autoware_auto_msgs::msg::AckermannControlCommand > received_ctrl_command_
autoware_msgs::msg::ControlCommandStamped generate_command() override
Extending class provided method which should generate a command message which will be published to th...
std::string get_version_id() override
Returns the version id of this plugin.
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.
Stuct containing the algorithm configuration values for trajectory_follower_wrapper.