Autonomous Racing  1
f1tenth Project Group of Technical University Dortmund, Germany
navigation_stack_control_converter.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/ros.h>
4 
5 #include <drive_msgs/drive_param.h>
6 #include <geometry_msgs/Twist.h>
7 
8 constexpr const char* TOPIC_DRIVE_PARAM = "input/drive_param/autonomous";
9 constexpr const char* TOPIC_CMD_VEL = "cmd_vel";
10 
11 constexpr double VELOCITY_THRESHOLD = 0.001;
12 constexpr double ANGULAR_VELOCITY_THRESHOLD = 0.000001;
13 
20 {
21  public:
27 
28  private:
33  ros::NodeHandle m_node_handle;
34 
39  ros::Subscriber m_command_velocity_subscriber;
40 
45  ros::Publisher m_drive_param_publisher;
46 
47  void convertCallback(const geometry_msgs::Twist::ConstPtr& cmd_vel_message);
48 };
NavigationStackControlConverter()
Initializes the publisher and subscriber.
This converter class converts "cmd_vel" messages to "drive_param" messages. The linear and angular ve...