kobuki_ros.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Yujin Robot.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Yujin Robot nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
35 /*****************************************************************************
36  ** Includes
37  *****************************************************************************/
38 
39 #include <float.h>
40 #include <tf/tf.h>
42 #include <kobuki_msgs/VersionInfo.h>
44 
45 /*****************************************************************************
46  ** Namespaces
47  *****************************************************************************/
48 
49 namespace kobuki
50 {
51 
52 /*****************************************************************************
53  ** Implementation [KobukiRos]
54  *****************************************************************************/
55 
61 KobukiRos::KobukiRos(std::string& node_name) :
62  name(node_name), cmd_vel_timed_out_(false), serial_timed_out_(false),
63  slot_version_info(&KobukiRos::publishVersionInfo, *this),
64  slot_controller_info(&KobukiRos::publishControllerInfo, *this),
65  slot_stream_data(&KobukiRos::processStreamData, *this),
66  slot_button_event(&KobukiRos::publishButtonEvent, *this),
67  slot_bumper_event(&KobukiRos::publishBumperEvent, *this),
68  slot_cliff_event(&KobukiRos::publishCliffEvent, *this),
69  slot_wheel_event(&KobukiRos::publishWheelEvent, *this),
70  slot_power_event(&KobukiRos::publishPowerEvent, *this),
71  slot_input_event(&KobukiRos::publishInputEvent, *this),
72  slot_robot_event(&KobukiRos::publishRobotEvent, *this),
73  slot_debug(&KobukiRos::rosDebug, *this),
74  slot_info(&KobukiRos::rosInfo, *this),
75  slot_warn(&KobukiRos::rosWarn, *this),
76  slot_error(&KobukiRos::rosError, *this),
77  slot_named(&KobukiRos::rosNamed, *this),
78  slot_raw_data_command(&KobukiRos::publishRawDataCommand, *this),
79  slot_raw_data_stream(&KobukiRos::publishRawDataStream, *this),
80  slot_raw_control_command(&KobukiRos::publishRawControlCommand, *this)
81 {
82  updater.setHardwareID("Kobuki");
93 }
94 
100 {
101  ROS_INFO_STREAM("Kobuki : waiting for kobuki thread to finish [" << name << "].");
102 }
103 
105 {
106  /*********************
107  ** Communications
108  **********************/
109  advertiseTopics(nh);
110  subscribeTopics(nh);
111 
112  /*********************
113  ** Slots
114  **********************/
115  slot_stream_data.connect(name + std::string("/stream_data"));
116  slot_version_info.connect(name + std::string("/version_info"));
117  slot_controller_info.connect(name + std::string("/controller_info"));
118  slot_button_event.connect(name + std::string("/button_event"));
119  slot_bumper_event.connect(name + std::string("/bumper_event"));
120  slot_cliff_event.connect(name + std::string("/cliff_event"));
121  slot_wheel_event.connect(name + std::string("/wheel_event"));
122  slot_power_event.connect(name + std::string("/power_event"));
123  slot_input_event.connect(name + std::string("/input_event"));
124  slot_robot_event.connect(name + std::string("/robot_event"));
125  slot_debug.connect(name + std::string("/ros_debug"));
126  slot_info.connect(name + std::string("/ros_info"));
127  slot_warn.connect(name + std::string("/ros_warn"));
128  slot_error.connect(name + std::string("/ros_error"));
129  slot_named.connect(name + std::string("/ros_named"));
130  slot_raw_data_command.connect(name + std::string("/raw_data_command"));
131  slot_raw_data_stream.connect(name + std::string("/raw_data_stream"));
132  slot_raw_control_command.connect(name + std::string("/raw_control_command"));
133 
134  /*********************
135  ** Driver Parameters
136  **********************/
137  Parameters parameters;
138 
139  nh.param("acceleration_limiter", parameters.enable_acceleration_limiter, false);
140  nh.param("battery_capacity", parameters.battery_capacity, Battery::capacity);
141  nh.param("battery_low", parameters.battery_low, Battery::low);
142  nh.param("battery_dangerous", parameters.battery_dangerous, Battery::dangerous);
143 
144  parameters.sigslots_namespace = name; // name is automatically picked up by device_nodelet parent.
145  if (!nh.getParam("device_port", parameters.device_port))
146  {
147  ROS_ERROR_STREAM("Kobuki : no device port given on the parameter server (e.g. /dev/ttyUSB0)[" << name << "].");
148  return false;
149  }
150 
151  /*********************
152  ** Joint States
153  **********************/
154  std::string robot_description, wheel_left_joint_name, wheel_right_joint_name;
155 
156  nh.param("wheel_left_joint_name", wheel_left_joint_name, std::string("wheel_left_joint"));
157  nh.param("wheel_right_joint_name", wheel_right_joint_name, std::string("wheel_right_joint"));
158 
159  // minimalistic check: are joint names present on robot description file?
160  if (!nh_pub.getParam("robot_description", robot_description))
161  {
162  ROS_WARN("Kobuki : no robot description given on the parameter server");
163  }
164  else
165  {
166  if (robot_description.find(wheel_left_joint_name) == std::string::npos) {
167  ROS_WARN("Kobuki : joint name %s not found on robot description", wheel_left_joint_name.c_str());
168  }
169 
170  if (robot_description.find(wheel_right_joint_name) == std::string::npos) {
171  ROS_WARN("Kobuki : joint name %s not found on robot description", wheel_right_joint_name.c_str());
172  }
173  }
174  joint_states.name.push_back(wheel_left_joint_name);
175  joint_states.name.push_back(wheel_right_joint_name);
176  joint_states.position.resize(2,0.0);
177  joint_states.velocity.resize(2,0.0);
178  joint_states.effort.resize(2,0.0);
179 
180  /*********************
181  ** Validation
182  **********************/
183  if (!parameters.validate())
184  {
185  ROS_ERROR_STREAM("Kobuki : parameter configuration failed [" << name << "].");
186  ROS_ERROR_STREAM("Kobuki : " << parameters.error_msg << "[" << name << "]");
187  return false;
188  }
189  else
190  {
191  if (parameters.simulation)
192  {
193  ROS_INFO("Kobuki : driver going into loopback (simulation) mode.");
194  }
195  else
196  {
197  ROS_INFO_STREAM("Kobuki : configured for connection on device_port "
198  << parameters.device_port << " [" << name << "].");
199  ROS_INFO_STREAM("Kobuki : driver running in normal (non-simulation) mode" << " [" << name << "].");
200  }
201  }
202 
203  odometry.init(nh, name);
204 
205  /*********************
206  ** Driver Init
207  **********************/
208  try
209  {
210  kobuki.init(parameters);
211  ros::Duration(0.25).sleep(); // wait for some data to come in.
212  if ( !kobuki.isAlive() ) {
213  ROS_WARN_STREAM("Kobuki : no data stream, is kobuki turned on?");
214  // don't need to return false here - simply turning kobuki on while spin()'ing should resurrect the situation.
215  }
216  kobuki.enable();
217  }
218  catch (const ecl::StandardException &e)
219  {
220  switch (e.flag())
221  {
222  case (ecl::OpenError):
223  {
224  ROS_ERROR_STREAM("Kobuki : could not open connection [" << parameters.device_port << "][" << name << "].");
225  break;
226  }
227  default:
228  {
229  ROS_ERROR_STREAM("Kobuki : initialisation failed [" << name << "].");
230  ROS_DEBUG_STREAM(e.what());
231  break;
232  }
233  }
234  return false;
235  }
236  // kobuki.printSigSlotConnections();
237  return true;
238 }
249 {
250  if ( kobuki.isShutdown() )
251  {
252  ROS_ERROR_STREAM("Kobuki : Driver has been shutdown. Stopping update loop. [" << name << "].");
253  return false;
254  }
255 
256  if ( (kobuki.isEnabled() == true) && odometry.commandTimeout())
257  {
258  if ( !cmd_vel_timed_out_ )
259  {
260  kobuki.setBaseControl(0, 0);
261  cmd_vel_timed_out_ = true;
262  ROS_WARN("Kobuki : Incoming velocity commands not received for more than %.2f seconds -> zero'ing velocity commands", odometry.timeout().toSec());
263  }
264  }
265  else
266  {
267  cmd_vel_timed_out_ = false;
268  }
269 
270  bool is_alive = kobuki.isAlive();
271  if ( watchdog_diagnostics.isAlive() && !is_alive )
272  {
273  if ( !serial_timed_out_ )
274  {
275  ROS_ERROR_STREAM("Kobuki : Timed out while waiting for serial data stream [" << name << "].");
276  serial_timed_out_ = true;
277  }
278  else
279  {
280  serial_timed_out_ = false;
281  }
282  }
283 
284  watchdog_diagnostics.update(is_alive);
285  battery_diagnostics.update(kobuki.batteryStatus());
286  cliff_diagnostics.update(kobuki.getCoreSensorData().cliff, kobuki.getCliffData());
287  bumper_diagnostics.update(kobuki.getCoreSensorData().bumper);
288  wheel_diagnostics.update(kobuki.getCoreSensorData().wheel_drop);
289  motor_diagnostics.update(kobuki.getCurrentData().current);
290  state_diagnostics.update(kobuki.isEnabled());
291  gyro_diagnostics.update(kobuki.getInertiaData().angle);
292  dinput_diagnostics.update(kobuki.getGpInputData().digital_input);
293  ainput_diagnostics.update(kobuki.getGpInputData().analog_input);
294  updater.update();
295 
296  return true;
297 }
298 
304 {
305  /*********************
306  ** Turtlebot Required
307  **********************/
308  joint_state_publisher = nh.advertise <sensor_msgs::JointState>("joint_states",100);
309 
310  /*********************
311  ** Kobuki Esoterics
312  **********************/
313  version_info_publisher = nh.advertise < kobuki_msgs::VersionInfo > ("version_info", 100, true); // latched publisher
314  controller_info_publisher = nh.advertise < kobuki_msgs::ControllerInfo > ("controller_info", 100, true); // latched publisher
315  button_event_publisher = nh.advertise < kobuki_msgs::ButtonEvent > ("events/button", 100);
316  bumper_event_publisher = nh.advertise < kobuki_msgs::BumperEvent > ("events/bumper", 100);
317  cliff_event_publisher = nh.advertise < kobuki_msgs::CliffEvent > ("events/cliff", 100);
318  wheel_event_publisher = nh.advertise < kobuki_msgs::WheelDropEvent > ("events/wheel_drop", 100);
319  power_event_publisher = nh.advertise < kobuki_msgs::PowerSystemEvent > ("events/power_system", 100);
320  input_event_publisher = nh.advertise < kobuki_msgs::DigitalInputEvent > ("events/digital_input", 100);
321  robot_event_publisher = nh.advertise < kobuki_msgs::RobotStateEvent > ("events/robot_state", 100, true); // also latched
322  sensor_state_publisher = nh.advertise < kobuki_msgs::SensorState > ("sensors/core", 100);
323  dock_ir_publisher = nh.advertise < kobuki_msgs::DockInfraRed > ("sensors/dock_ir", 100);
324  imu_data_publisher = nh.advertise < sensor_msgs::Imu > ("sensors/imu_data", 100);
325  raw_imu_data_publisher = nh.advertise < sensor_msgs::Imu > ("sensors/imu_data_raw", 100);
326  raw_data_command_publisher = nh.advertise< std_msgs::String > ("debug/raw_data_command", 100);
327  raw_data_stream_publisher = nh.advertise< std_msgs::String > ("debug/raw_data_stream", 100);
328  raw_control_command_publisher = nh.advertise< std_msgs::Int16MultiArray > ("debug/raw_control_command", 100);
329 }
330 
336 {
337  velocity_command_subscriber = nh.subscribe(std::string("commands/velocity"), 10, &KobukiRos::subscribeVelocityCommand, this);
338  led1_command_subscriber = nh.subscribe(std::string("commands/led1"), 10, &KobukiRos::subscribeLed1Command, this);
339  led2_command_subscriber = nh.subscribe(std::string("commands/led2"), 10, &KobukiRos::subscribeLed2Command, this);
340  digital_output_command_subscriber = nh.subscribe(std::string("commands/digital_output"), 10, &KobukiRos::subscribeDigitalOutputCommand, this);
341  external_power_command_subscriber = nh.subscribe(std::string("commands/external_power"), 10, &KobukiRos::subscribeExternalPowerCommand, this);
342  sound_command_subscriber = nh.subscribe(std::string("commands/sound"), 10, &KobukiRos::subscribeSoundCommand, this);
343  reset_odometry_subscriber = nh.subscribe("commands/reset_odometry", 10, &KobukiRos::subscribeResetOdometry, this);
344  motor_power_subscriber = nh.subscribe("commands/motor_power", 10, &KobukiRos::subscribeMotorPower, this);
345  controller_info_command_subscriber = nh.subscribe(std::string("commands/controller_info"), 10, &KobukiRos::subscribeControllerInfoCommand, this);
346 }
347 
348 
349 } // namespace kobuki
350 
BatteryTask battery_diagnostics
Definition: kobuki_ros.hpp:205
ecl::Slot< const RobotEvent & > slot_robot_event
Definition: kobuki_ros.hpp:146
WheelDropTask wheel_diagnostics
Definition: kobuki_ros.hpp:209
bool isAlive() const
Definition: diagnostics.hpp:57
ros::Publisher wheel_event_publisher
Definition: kobuki_ros.hpp:110
void update(const std::vector< uint16_t > &new_values)
ecl::Slot< const std::string & > slot_info
Definition: kobuki_ros.hpp:147
static double low
void subscribeMotorPower(const kobuki_msgs::MotorPowerConstPtr msg)
void update(uint16_t new_status)
void subscribeDigitalOutputCommand(const kobuki_msgs::DigitalOutputConstPtr)
const char * what() const
ecl::Slot< const std::vector< std::string > & > slot_named
Definition: kobuki_ros.hpp:148
ros::Publisher robot_event_publisher
Definition: kobuki_ros.hpp:109
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
KobukiRos(std::string &node_name)
Default constructor.
Definition: kobuki_ros.cpp:61
ecl::Slot< const ButtonEvent & > slot_button_event
Definition: kobuki_ros.hpp:140
void setHardwareID(const std::string &hwid)
bool sleep() const
void update(const bool &is_alive)
Definition: diagnostics.hpp:56
ros::Publisher raw_imu_data_publisher
Definition: kobuki_ros.hpp:108
ros::Publisher version_info_publisher
Definition: kobuki_ros.hpp:107
std::string error_msg
void add(const std::string &name, TaskFunction f)
std::string device_port
void update(bool new_state)
ecl::Slot< const BumperEvent & > slot_bumper_event
Definition: kobuki_ros.hpp:141
ecl::Slot slot_stream_data
Definition: kobuki_ros.hpp:138
ecl::Slot< const PowerEvent & > slot_power_event
Definition: kobuki_ros.hpp:144
std::string sigslots_namespace
#define ROS_WARN(...)
AnalogInputTask ainput_diagnostics
Definition: kobuki_ros.hpp:214
sensor_msgs::JointState joint_states
Definition: kobuki_ros.hpp:99
void init(ros::NodeHandle &nh, const std::string &name)
Definition: odometry.cpp:33
WallSensorTask bumper_diagnostics
Definition: kobuki_ros.hpp:208
void subscribeControllerInfoCommand(const kobuki_msgs::ControllerInfoConstPtr msg)
MotorCurrentTask motor_diagnostics
Definition: kobuki_ros.hpp:210
ecl::Slot< Command::Buffer & > slot_raw_data_command
Definition: kobuki_ros.hpp:149
void update(const uint8_t &new_status)
Definition: diagnostics.hpp:99
ros::Publisher bumper_event_publisher
Definition: kobuki_ros.hpp:110
void subscribeSoundCommand(const kobuki_msgs::SoundConstPtr)
Play a predefined sound (single sound or sound sequence)
ecl::Slot< PacketFinder::BufferType & > slot_raw_data_stream
Definition: kobuki_ros.hpp:150
void subscribeLed1Command(const kobuki_msgs::LedConstPtr)
ros::Publisher cliff_event_publisher
Definition: kobuki_ros.hpp:110
ros::Publisher raw_data_stream_publisher
Definition: kobuki_ros.hpp:111
ros::Publisher controller_info_publisher
Definition: kobuki_ros.hpp:107
void update(const uint8_t &new_status)
Definition: diagnostics.hpp:86
const ros::Duration & timeout() const
Definition: odometry.hpp:47
ecl::Slot< const std::string & > slot_warn
Definition: kobuki_ros.hpp:147
void update(const Battery &battery)
Definition: diagnostics.hpp:43
ros::Publisher input_event_publisher
Definition: kobuki_ros.hpp:109
ros::Publisher imu_data_publisher
Definition: kobuki_ros.hpp:108
void update(const std::vector< uint8_t > &new_values)
#define ROS_INFO(...)
Wraps the kobuki driver in a ROS-specific library.
ros::Subscriber digital_output_command_subscriber
Definition: kobuki_ros.hpp:113
bool param(const std::string &param_name, T &param_val, const T &default_val) const
GyroSensorTask gyro_diagnostics
Definition: kobuki_ros.hpp:212
WatchdogTask watchdog_diagnostics
Definition: kobuki_ros.hpp:206
ecl::Slot< const InputEvent & > slot_input_event
Definition: kobuki_ros.hpp:145
void subscribeExternalPowerCommand(const kobuki_msgs::ExternalPowerConstPtr)
ros::Publisher sensor_state_publisher
Definition: kobuki_ros.hpp:108
ecl::Slot< const VersionInfo & > slot_version_info
Definition: kobuki_ros.hpp:137
ros::Subscriber external_power_command_subscriber
Definition: kobuki_ros.hpp:113
ecl::Slot< const CliffEvent & > slot_cliff_event
Definition: kobuki_ros.hpp:142
void subscribeLed2Command(const kobuki_msgs::LedConstPtr)
ros::Subscriber controller_info_command_subscriber
Definition: kobuki_ros.hpp:114
ros::Subscriber velocity_command_subscriber
Definition: kobuki_ros.hpp:113
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool commandTimeout() const
Definition: odometry.cpp:79
MotorStateTask state_diagnostics
Definition: kobuki_ros.hpp:211
ros::Publisher raw_data_command_publisher
Definition: kobuki_ros.hpp:111
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
ros::Subscriber led2_command_subscriber
Definition: kobuki_ros.hpp:115
void connect(const std::string &topic)
DigitalInputTask dinput_diagnostics
Definition: kobuki_ros.hpp:213
bool init(ros::NodeHandle &nh, ros::NodeHandle &nh_pub)
Definition: kobuki_ros.cpp:104
#define ROS_INFO_STREAM(args)
ros::Subscriber led1_command_subscriber
Definition: kobuki_ros.hpp:115
ros::Publisher power_event_publisher
Definition: kobuki_ros.hpp:110
ros::Publisher joint_state_publisher
Definition: kobuki_ros.hpp:108
bool getParam(const std::string &key, std::string &s) const
void update(int16_t new_heading)
CliffSensorTask cliff_diagnostics
Definition: kobuki_ros.hpp:207
ros::Subscriber motor_power_subscriber
Definition: kobuki_ros.hpp:116
void advertiseTopics(ros::NodeHandle &nh)
Definition: kobuki_ros.cpp:303
static double capacity
std::string name
Definition: kobuki_ros.hpp:97
ros::Publisher dock_ir_publisher
Definition: kobuki_ros.hpp:108
ros::Publisher raw_control_command_publisher
Definition: kobuki_ros.hpp:111
ros::Subscriber reset_odometry_subscriber
Definition: kobuki_ros.hpp:116
#define ROS_ERROR_STREAM(args)
static double dangerous
void subscribeResetOdometry(const std_msgs::EmptyConstPtr)
Reset the odometry variables.
void subscribeTopics(ros::NodeHandle &nh)
Definition: kobuki_ros.cpp:335
ecl::Slot< const std::string & > slot_error
Definition: kobuki_ros.hpp:147
bool enable_acceleration_limiter
ecl::Slot< const std::string & > slot_debug
Definition: kobuki_ros.hpp:147
ros::Publisher button_event_publisher
Definition: kobuki_ros.hpp:109
void update(const uint8_t &new_status, const Cliff::Data &new_values)
Definition: diagnostics.hpp:70
diagnostic_updater::Updater updater
Definition: kobuki_ros.hpp:204
ecl::Slot< const std::vector< short > & > slot_raw_control_command
Definition: kobuki_ros.hpp:151
void subscribeVelocityCommand(const geometry_msgs::TwistConstPtr)
ros::Subscriber sound_command_subscriber
Definition: kobuki_ros.hpp:115
ecl::Slot< const WheelEvent & > slot_wheel_event
Definition: kobuki_ros.hpp:143
const ErrorFlag & flag() const
ecl::Slot slot_controller_info
Definition: kobuki_ros.hpp:139


kobuki_node
Author(s): Daniel Stonier, Younghun Ju, Jorge Santos Simon
autogenerated on Mon Jun 10 2019 13:45:13