Go to the documentation of this file.
19 #ifndef TURTLEBOT3_FAKE_H_
20 #define TURTLEBOT3_FAKE_H_
26 #include <std_msgs/Int32.h>
27 #include <sensor_msgs/Imu.h>
28 #include <sensor_msgs/JointState.h>
29 #include <geometry_msgs/Vector3.h>
30 #include <geometry_msgs/Twist.h>
33 #include <nav_msgs/Odometry.h>
35 #include <turtlebot3_msgs/SensorState.h>
39 #define WHEEL_RADIUS 0.033 // meter
44 #define MAX_LINEAR_VELOCITY 0.22 // m/s
45 #define MAX_ANGULAR_VELOCITY 2.84 // rad/s
46 #define VELOCITY_STEP 0.01 // m/s
47 #define VELOCITY_LINEAR_X 0.01 // m/s
48 #define VELOCITY_ANGULAR_Z 0.1 // rad/s
49 #define SCALE_VELOCITY_LINEAR_X 1
50 #define SCALE_VELOCITY_ANGULAR_Z 1
52 #define DEG2RAD(x) (x * 0.01745329252) // *PI/180
53 #define RAD2DEG(x) (x * 57.2957795131) // *180/PI
55 #define TORQUE_ENABLE 1 // Value for enabling the torque of motor
56 #define TORQUE_DISABLE 0 // Value for disabling the torque of motor
111 void updateTF(geometry_msgs::TransformStamped& odom_tf);
114 #endif // TURTLEBOT3_FAKE_H_
std::string joint_states_name_[2]
ros::Publisher joint_states_pub_
ros::Time last_cmd_vel_time_
double goal_linear_velocity_
ros::Time prev_update_time_
double wheel_speed_cmd_[2]
bool updateOdometry(ros::Duration diff_time)
void commandVelocityCallback(const geometry_msgs::TwistConstPtr cmd_vel_msg)
void updateTF(geometry_msgs::TransformStamped &odom_tf)
ros::Subscriber cmd_vel_sub_
tf::TransformBroadcaster tf_broadcaster_
double goal_angular_velocity_
sensor_msgs::JointState joint_states_
turtlebot3_fake
Author(s): Pyo
, Darby Lim
autogenerated on Wed Mar 2 2022 01:10:17