|
18 | 18 |
|
19 | 19 | #ifndef TURTLEBOT3_CORE_CONFIG_H_
|
20 | 20 | #define TURTLEBOT3_CORE_CONFIG_H_
|
| 21 | +// #define NOETIC_SUPPORT //uncomment this if writing code for ROS1 Noetic |
21 | 22 |
|
22 | 23 | #include <ros.h>
|
23 | 24 | #include <ros/time.h>
|
24 | 25 | #include <std_msgs/Bool.h>
|
25 | 26 | #include <std_msgs/Empty.h>
|
26 | 27 | #include <std_msgs/Int32.h>
|
27 |
| -#include <sensor_msgs/Imu.h> |
28 | 28 | #include <sensor_msgs/JointState.h>
|
29 |
| -#include <sensor_msgs/BatteryState.h> |
30 |
| -#include <sensor_msgs/MagneticField.h> |
31 | 29 | #include <geometry_msgs/Vector3.h>
|
32 |
| -#include <geometry_msgs/Twist.h> |
33 | 30 | #include <tf/tf.h>
|
34 | 31 | #include <tf/transform_broadcaster.h>
|
35 | 32 | #include <nav_msgs/Odometry.h>
|
|
43 | 40 |
|
44 | 41 | #include <math.h>
|
45 | 42 |
|
46 |
| -#define FIRMWARE_VER "1.2.3" |
| 43 | +#define FIRMWARE_VER "1.2.6" |
47 | 44 |
|
48 | 45 | #define CONTROL_MOTOR_SPEED_FREQUENCY 30 //hz
|
49 | 46 | #define CONTROL_MOTOR_TIMEOUT 500 //ms
|
@@ -168,7 +165,11 @@ sensor_msgs::JointState joint_states;
|
168 | 165 | ros::Publisher joint_states_pub("joint_states", &joint_states);
|
169 | 166 |
|
170 | 167 | // Battey state of Turtlebot3
|
| 168 | +#if defined NOETIC_SUPPORT |
| 169 | +sensor_msgs::BatteryStateNoetic battery_state_msg; |
| 170 | +#else |
171 | 171 | sensor_msgs::BatteryState battery_state_msg;
|
| 172 | +#endif |
172 | 173 | ros::Publisher battery_state_pub("battery_state", &battery_state_msg);
|
173 | 174 |
|
174 | 175 | // Magnetic field
|
|
0 commit comments