20 namespace std_ph = std::placeholders;
35 auto error_double = update_params<double>({
41 rcl_interfaces::msg::SetParametersResult result;
43 result.successful = !error_double;
58 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"Loaded Params: " <<
config_);
64 rclcpp::SubscriptionOptions intra_proc_disabled;
65 intra_proc_disabled.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
67 auto sub_qos_transient_local = rclcpp::QoS(rclcpp::KeepAll());
68 sub_qos_transient_local.transient_local();
70 control_cmd_sub_ = create_subscription<autoware_auto_msgs::msg::AckermannControlCommand>(
"trajectory_follower/control_cmd", sub_qos_transient_local,
74 autoware_traj_pub_ = create_publisher<autoware_auto_msgs::msg::Trajectory>(
"trajectory_follower/reference_trajectory", 10);
75 autoware_state_pub_ = create_publisher<autoware_auto_msgs::msg::VehicleKinematicState>(
"trajectory_follower/current_kinematic_state", 10);
80 std::chrono::milliseconds(33),
84 return CallbackReturn::SUCCESS;
90 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"In autoware info timer callback");
110 if (std::abs(twist.twist.linear.x) <
EPSILON )
116 return steering_angle;
121 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"In ackermann control callback");
128 autoware_auto_msgs::msg::VehicleKinematicState state;
129 state.header = pose.header;
130 state.header.frame_id =
"map";
131 state.state.x = pose.pose.position.x;
132 state.state.y = pose.pose.position.y;
133 state.state.z = pose.pose.position.z;
134 state.state.heading.real = pose.pose.orientation.w;
135 state.state.heading.imag = pose.pose.orientation.z;
138 state.state.longitudinal_velocity_mps = twist.twist.linear.x;
139 state.state.lateral_velocity_mps = twist.twist.linear.y;
140 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"front_wheel_angle_rad: " << state.state.front_wheel_angle_rad);
149 autoware_msgs::msg::ControlCommandStamped return_cmd;
150 return_cmd.header.stamp = cmd.stamp;
152 return_cmd.cmd.linear_acceleration = cmd.longitudinal.acceleration;
153 return_cmd.cmd.linear_velocity = cmd.longitudinal.speed;
154 return_cmd.cmd.steering_angle = cmd.lateral.steering_tire_angle;
156 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"generated command cmd.stamp: " <<
std::to_string(rclcpp::Time(cmd.stamp).seconds()));
157 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"generated command cmd.longitudinal.acceleration: " << cmd.longitudinal.acceleration);
158 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"generated command cmd.longitudinal.speed: " << cmd.longitudinal.speed);
159 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"generated command cmd.lateral.steering_tire_angle: " << cmd.lateral.steering_tire_angle);
160 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"generated command cmd.lateral.steering_tire_rotation_rate: " << cmd.lateral.steering_tire_rotation_rate);
168 autoware_msgs::msg::ControlCommandStamped converted_cmd;
172 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"Insufficient data, empty control command generated");
173 return converted_cmd;
179 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"trajectory_follower_wrapper"),
"Control Command is old, empty control command generated");
180 return converted_cmd;
185 return converted_cmd;
190 double difference = std::abs(this->now().seconds() - rclcpp::Time(cmd.stamp).seconds());
213#include "rclcpp_components/register_node_macro.hpp"
boost::optional< geometry_msgs::msg::TwistStamped > current_twist_
The most recent velocity message received by this node.
boost::optional< carma_planning_msgs::msg::TrajectoryPlan > current_trajectory_
The most recent trajectory received by this plugin.
boost::optional< geometry_msgs::msg::PoseStamped > current_pose_
The most recent pose message received by this node.
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
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.
autoware_auto_msgs::msg::Trajectory process_trajectory_plan(const carma_planning_msgs::msg::TrajectoryPlan &tp, double vehicle_response_lag)
Given a carma type of trajectory_plan, generate autoware type of trajectory accounting for speed_lag ...
auto to_string(const UtmZone &zone) -> std::string
Stuct containing the algorithm configuration values for trajectory_follower_wrapper.
double vehicle_response_lag
double incoming_cmd_time_threshold
double vehicle_wheel_base