Skip to content

Commit

Permalink
Merge pull request #257 from ROBOTIS-GIT/develop
Browse files Browse the repository at this point in the history
Develop
  • Loading branch information
ROBOTIS-Will committed Oct 23, 2020
2 parents dd344c4 + 24156d4 commit fa428cf
Show file tree
Hide file tree
Showing 11 changed files with 461 additions and 27 deletions.
6 changes: 2 additions & 4 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,9 @@ notifications:
on_success: change
on_failure: always
recipients:
- [email protected]
- [email protected]
- [email protected]
- [email protected]
- [email protected]

branches:
only:
- master
- develop
Original file line number Diff line number Diff line change
Expand Up @@ -18,18 +18,15 @@

#ifndef TURTLEBOT3_CORE_CONFIG_H_
#define TURTLEBOT3_CORE_CONFIG_H_
// #define NOETIC_SUPPORT //uncomment this if writing code for ROS1 Noetic

#include <ros.h>
#include <ros/time.h>
#include <std_msgs/Bool.h>
#include <std_msgs/Empty.h>
#include <std_msgs/Int32.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/JointState.h>
#include <sensor_msgs/BatteryState.h>
#include <sensor_msgs/MagneticField.h>
#include <geometry_msgs/Vector3.h>
#include <geometry_msgs/Twist.h>
#include <tf/tf.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
Expand All @@ -43,7 +40,7 @@

#include <math.h>

#define FIRMWARE_VER "1.2.3"
#define FIRMWARE_VER "1.2.6"

#define CONTROL_MOTOR_SPEED_FREQUENCY 30 //hz
#define CONTROL_MOTOR_TIMEOUT 500 //ms
Expand Down Expand Up @@ -168,7 +165,11 @@ sensor_msgs::JointState joint_states;
ros::Publisher joint_states_pub("joint_states", &joint_states);

// Battey state of Turtlebot3
#if defined NOETIC_SUPPORT
sensor_msgs::BatteryStateNoetic battery_state_msg;
#else
sensor_msgs::BatteryState battery_state_msg;
#endif
ros::Publisher battery_state_pub("battery_state", &battery_state_msg);

// Magnetic field
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,18 +18,15 @@

#ifndef TURTLEBOT3_CORE_CONFIG_H_
#define TURTLEBOT3_CORE_CONFIG_H_
// #define NOETIC_SUPPORT //uncomment this if writing code for ROS1 Noetic

#include <ros.h>
#include <ros/time.h>
#include <std_msgs/Bool.h>
#include <std_msgs/Empty.h>
#include <std_msgs/Int32.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/JointState.h>
#include <sensor_msgs/BatteryState.h>
#include <sensor_msgs/MagneticField.h>
#include <geometry_msgs/Vector3.h>
#include <geometry_msgs/Twist.h>
#include <tf/tf.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
Expand All @@ -43,7 +40,7 @@

#include <math.h>

#define FIRMWARE_VER "1.2.3"
#define FIRMWARE_VER "1.2.6"

#define CONTROL_MOTOR_SPEED_FREQUENCY 30 //hz
#define CONTROL_MOTOR_TIMEOUT 500 //ms
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

#ifndef TURTLEBOT3_WITH_OPEN_MANIPULATOR_CORE_CONFIG_H_
#define TURTLEBOT3_WITH_OPEN_MANIPULATOR_CORE_CONFIG_H_
// #define NOETIC_SUPPORT //uncomment this if writing code for ROS1 Noetic

#include <ros.h>
#include <ros/time.h>
Expand All @@ -26,10 +27,7 @@
#include <std_msgs/Int32.h>
#include <std_msgs/Float64.h>
#include <std_msgs/Float64MultiArray.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/JointState.h>
#include <sensor_msgs/BatteryState.h>
#include <sensor_msgs/MagneticField.h>
#include <geometry_msgs/Vector3.h>
#include <geometry_msgs/Twist.h>
#include <tf/tf.h>
Expand All @@ -45,7 +43,7 @@

#include <math.h>

#define FIRMWARE_VER "2.0.1"
#define FIRMWARE_VER "2.0.2"

#define CONTROL_MOTOR_SPEED_FREQUENCY 30 //hz
#define IMU_PUBLISH_FREQUENCY 200 //hz
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,14 @@
#include <IMU.h>

#include <sensor_msgs/Imu.h>
#include <sensor_msgs/BatteryState.h>
#include <sensor_msgs/MagneticField.h>

#if defined NOETIC_SUPPORT
#include <sensor_msgs/BatteryStateNoetic.h>
#else
#include <sensor_msgs/BatteryState.h>
#endif

#include "OLLO.h"

#define ACCEL_FACTOR 0.000598550415 // (ADC_Value / Scale) * 9.80665 => Range : +- 2[g]
Expand Down Expand Up @@ -98,7 +103,11 @@ class Turtlebot3Sensor
void setLedPattern(double linear_vel, double angular_vel);
private:
sensor_msgs::Imu imu_msg_;
sensor_msgs::BatteryState battery_state_msg_;
#if defined NOETIC_SUPPORT
sensor_msgs::BatteryStateNoetic battery_state_msg_;
#else
sensor_msgs::BatteryState battery_state_msg_;
#endif
sensor_msgs::MagneticField mag_msg_;

cIMU imu_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,10 @@ bool Turtlebot3Sensor::init(void)

uint8_t get_error_code = 0x00;

#if defined NOETIC_SUPPORT
battery_state_msg_.temperature = NAN;
#endif

battery_state_msg_.current = NAN;
battery_state_msg_.charge = NAN;
battery_state_msg_.capacity = NAN;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -323,4 +323,4 @@ namespace sensor_msgs
};

}
#endif
#endif
Loading

0 comments on commit fa428cf

Please sign in to comment.