19 #ifndef TURTLEBOT3_DRIVE_H_ 20 #define TURTLEBOT3_DRIVE_H_ 24 #include <sensor_msgs/LaserScan.h> 25 #include <geometry_msgs/Twist.h> 26 #include <nav_msgs/Odometry.h> 28 #define DEG2RAD (M_PI / 180.0) 29 #define RAD2DEG (180.0 / M_PI) 35 #define LINEAR_VELOCITY 0.3 36 #define ANGULAR_VELOCITY 1.5 38 #define GET_TB3_DIRECTION 0 39 #define TB3_DRIVE_FORWARD 1 40 #define TB3_RIGHT_TURN 2 41 #define TB3_LEFT_TURN 3 82 #endif // TURTLEBOT3_DRIVE_H_ void laserScanMsgCallBack(const sensor_msgs::LaserScan::ConstPtr &msg)
double check_forward_dist_
ros::Publisher cmd_vel_pub_
void odomMsgCallBack(const nav_msgs::Odometry::ConstPtr &msg)
void updatecommandVelocity(double linear, double angular)
ros::Subscriber odom_sub_
ros::Subscriber laser_scan_sub_