kobuki_ros.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, Yujin Robot.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Yujin Robot nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00035 /*****************************************************************************
00036  ** Includes
00037  *****************************************************************************/
00038 
00039 #include <float.h>
00040 #include <tf/tf.h>
00041 #include <ecl/streams/string_stream.hpp>
00042 #include <kobuki_msgs/VersionInfo.h>
00043 #include "kobuki_node/kobuki_ros.hpp"
00044 
00045 /*****************************************************************************
00046  ** Namespaces
00047  *****************************************************************************/
00048 
00049 namespace kobuki
00050 {
00051 
00052 /*****************************************************************************
00053  ** Implementation [KobukiRos]
00054  *****************************************************************************/
00055 
00061 KobukiRos::KobukiRos(std::string& node_name) :
00062     name(node_name), cmd_vel_timed_out_(false), serial_timed_out_(false),
00063     slot_version_info(&KobukiRos::publishVersionInfo, *this),
00064     slot_stream_data(&KobukiRos::processStreamData, *this),
00065     slot_button_event(&KobukiRos::publishButtonEvent, *this),
00066     slot_bumper_event(&KobukiRos::publishBumperEvent, *this),
00067     slot_cliff_event(&KobukiRos::publishCliffEvent, *this),
00068     slot_wheel_event(&KobukiRos::publishWheelEvent, *this),
00069     slot_power_event(&KobukiRos::publishPowerEvent, *this),
00070     slot_input_event(&KobukiRos::publishInputEvent, *this),
00071     slot_robot_event(&KobukiRos::publishRobotEvent, *this),
00072     slot_debug(&KobukiRos::rosDebug, *this),
00073     slot_info(&KobukiRos::rosInfo, *this),
00074     slot_warn(&KobukiRos::rosWarn, *this),
00075     slot_error(&KobukiRos::rosError, *this),
00076     slot_raw_data_command(&KobukiRos::publishRawDataCommand, *this),
00077     slot_raw_data_stream(&KobukiRos::publishRawDataStream, *this)
00078 {
00079   updater.setHardwareID("Kobuki");
00080   updater.add(battery_diagnostics);
00081   updater.add(watchdog_diagnostics);
00082   updater.add(bumper_diagnostics);
00083   updater.add(cliff_diagnostics);
00084   updater.add(wheel_diagnostics);
00085   updater.add(motor_diagnostics);
00086   updater.add(state_diagnostics);
00087   updater.add(gyro_diagnostics);
00088   updater.add(dinput_diagnostics);
00089   updater.add(ainput_diagnostics);
00090 }
00091 
00096 KobukiRos::~KobukiRos()
00097 {
00098   ROS_INFO_STREAM("Kobuki : waiting for kobuki thread to finish [" << name << "].");
00099 }
00100 
00101 bool KobukiRos::init(ros::NodeHandle& nh)
00102 {
00103   /*********************
00104    ** Communications
00105    **********************/
00106   advertiseTopics(nh);
00107   subscribeTopics(nh);
00108 
00109   /*********************
00110    ** Slots
00111    **********************/
00112   slot_stream_data.connect(name + std::string("/stream_data"));
00113   slot_version_info.connect(name + std::string("/version_info"));
00114   slot_button_event.connect(name + std::string("/button_event"));
00115   slot_bumper_event.connect(name + std::string("/bumper_event"));
00116   slot_cliff_event.connect(name + std::string("/cliff_event"));
00117   slot_wheel_event.connect(name + std::string("/wheel_event"));
00118   slot_power_event.connect(name + std::string("/power_event"));
00119   slot_input_event.connect(name + std::string("/input_event"));
00120   slot_robot_event.connect(name + std::string("/robot_event"));
00121   slot_debug.connect(name + std::string("/ros_debug"));
00122   slot_info.connect(name + std::string("/ros_info"));
00123   slot_warn.connect(name + std::string("/ros_warn"));
00124   slot_error.connect(name + std::string("/ros_error"));
00125   slot_raw_data_command.connect(name + std::string("/raw_data_command"));
00126   slot_raw_data_stream.connect(name + std::string("/raw_data_stream"));
00127 
00128   /*********************
00129    ** Driver Parameters
00130    **********************/
00131   Parameters parameters;
00132 
00133   nh.param("acceleration_limiter", parameters.enable_acceleration_limiter, false);
00134   nh.param("battery_capacity", parameters.battery_capacity, Battery::capacity);
00135   nh.param("battery_low", parameters.battery_low, Battery::low);
00136   nh.param("battery_dangerous", parameters.battery_dangerous, Battery::dangerous);
00137 
00138   parameters.sigslots_namespace = name; // name is automatically picked up by device_nodelet parent.
00139   if (!nh.getParam("device_port", parameters.device_port))
00140   {
00141     ROS_ERROR_STREAM("Kobuki : no device port given on the parameter server (e.g. /dev/ttyUSB0)[" << name << "].");
00142     return false;
00143   }
00144 
00145   /*********************
00146    ** Joint States
00147    **********************/
00148   std::string robot_description, wheel_left_joint_name, wheel_right_joint_name;
00149 
00150   nh.param("wheel_left_joint_name", wheel_left_joint_name, std::string("wheel_left_joint"));
00151   nh.param("wheel_right_joint_name", wheel_right_joint_name, std::string("wheel_right_joint"));
00152 
00153   // minimalistic check: are joint names present on robot description file?
00154   if (!nh.getParam("/robot_description", robot_description))
00155   {
00156     ROS_WARN("Kobuki : no robot description given on the parameter server");
00157   }
00158   else
00159   {
00160     if (robot_description.find(wheel_left_joint_name) == std::string::npos) {
00161       ROS_WARN("Kobuki : joint name %s not found on robot description", wheel_left_joint_name.c_str());
00162     }
00163 
00164     if (robot_description.find(wheel_right_joint_name) == std::string::npos) {
00165       ROS_WARN("Kobuki : joint name %s not found on robot description", wheel_right_joint_name.c_str());
00166     }
00167   }
00168   joint_states.name.push_back(wheel_left_joint_name);
00169   joint_states.name.push_back(wheel_right_joint_name);
00170   joint_states.position.resize(2,0.0);
00171   joint_states.velocity.resize(2,0.0);
00172   joint_states.effort.resize(2,0.0);
00173 
00174   /*********************
00175    ** Validation
00176    **********************/
00177   if (!parameters.validate())
00178   {
00179     ROS_ERROR_STREAM("Kobuki : parameter configuration failed [" << name << "].");
00180     ROS_ERROR_STREAM("Kobuki : " << parameters.error_msg << "[" << name << "]");
00181     return false;
00182   }
00183   else
00184   {
00185     if (parameters.simulation)
00186     {
00187       ROS_INFO("Kobuki : driver going into loopback (simulation) mode.");
00188     }
00189     else
00190     {
00191       ROS_INFO_STREAM("Kobuki : configured for connection on device_port "
00192                       << parameters.device_port << " [" << name << "].");
00193       ROS_INFO_STREAM("Kobuki : driver running in normal (non-simulation) mode" << " [" << name << "].");
00194     }
00195   }
00196 
00197   odometry.init(nh, name);
00198 
00199   /*********************
00200    ** Driver Init
00201    **********************/
00202   try
00203   {
00204     kobuki.init(parameters);
00205     ros::Duration(0.25).sleep(); // wait for some data to come in.
00206     if ( !kobuki.isAlive() ) {
00207       ROS_ERROR_STREAM("Kobuki : no data stream, is Kobuki turned on?");
00208       // don't need to return false here - simply turning kobuki on while spin()'ing should resurrect the situation.
00209     }
00210     kobuki.enable();
00211   }
00212   catch (const ecl::StandardException &e)
00213   {
00214     switch (e.flag())
00215     {
00216       case (ecl::OpenError):
00217       {
00218         ROS_ERROR_STREAM("Kobuki : could not open connection [" << parameters.device_port << "][" << name << "].");
00219         break;
00220       }
00221       case (ecl::NotFoundError):
00222       {
00223         ROS_ERROR_STREAM("Kobuki : could not find the device [" << parameters.device_port << "][" << name << "].");
00224         break;
00225       }
00226       default:
00227       {
00228         ROS_ERROR_STREAM("Kobuki : initialisation failed [" << name << "].");
00229         ROS_DEBUG_STREAM(e.what());
00230         break;
00231       }
00232     }
00233     return false;
00234   }
00235 
00236   // kobuki.printSigSlotConnections();
00237   return true;
00238 }
00239 
00240 bool KobukiRos::update()
00241 {
00242   if ( kobuki.isShutdown() )
00243   {
00244     ROS_ERROR_STREAM("Kobuki : Driver has been shutdown. Stopping update loop. [" << name << "].");
00245     return false;
00246   }
00247 
00248   if ( (kobuki.isEnabled() == true) && odometry.commandTimeout())
00249   {
00250     if ( !cmd_vel_timed_out_ )
00251     {
00252       kobuki.setBaseControl(0, 0);
00253       cmd_vel_timed_out_ = true;
00254       ROS_WARN("Kobuki : Incoming velocity commands not received for more than %.2f seconds -> zero'ing velocity commands", odometry.timeout().toSec());
00255     }
00256   }
00257   else
00258   {
00259     cmd_vel_timed_out_ = false;
00260   }
00261 
00262   bool is_alive = kobuki.isAlive();
00263   if ( watchdog_diagnostics.isAlive() && !is_alive )
00264   {
00265     if ( !serial_timed_out_ )
00266     {
00267       ROS_ERROR_STREAM("Kobuki : Timed out while waiting for serial data stream [" << name << "].");
00268       serial_timed_out_ = true;
00269     }
00270     else
00271     {
00272       serial_timed_out_ = false;
00273     }
00274   }
00275 
00276   watchdog_diagnostics.update(is_alive);
00277   battery_diagnostics.update(kobuki.batteryStatus());
00278   cliff_diagnostics.update(kobuki.getCoreSensorData().cliff, kobuki.getCliffData());
00279   bumper_diagnostics.update(kobuki.getCoreSensorData().bumper);
00280   wheel_diagnostics.update(kobuki.getCoreSensorData().wheel_drop);
00281   motor_diagnostics.update(kobuki.getCurrentData().current);
00282   state_diagnostics.update(kobuki.isEnabled());
00283   gyro_diagnostics.update(kobuki.getInertiaData().angle);
00284   dinput_diagnostics.update(kobuki.getGpInputData().digital_input);
00285   ainput_diagnostics.update(kobuki.getGpInputData().analog_input);
00286   updater.update();
00287 
00288   return true;
00289 }
00290 
00295 void KobukiRos::advertiseTopics(ros::NodeHandle& nh)
00296 {
00297   /*********************
00298   ** Turtlebot Required
00299   **********************/
00300   joint_state_publisher = nh.advertise <sensor_msgs::JointState>("joint_states",100);
00301 
00302   /*********************
00303   ** Kobuki Esoterics
00304   **********************/
00305   version_info_publisher = nh.advertise < kobuki_msgs::VersionInfo > ("version_info",  100, true); // latched publisher
00306   button_event_publisher = nh.advertise < kobuki_msgs::ButtonEvent > ("events/button", 100);
00307   bumper_event_publisher = nh.advertise < kobuki_msgs::BumperEvent > ("events/bumper", 100);
00308   cliff_event_publisher  = nh.advertise < kobuki_msgs::CliffEvent >  ("events/cliff",  100);
00309   wheel_event_publisher  = nh.advertise < kobuki_msgs::WheelDropEvent > ("events/wheel_drop", 100);
00310   power_event_publisher  = nh.advertise < kobuki_msgs::PowerSystemEvent > ("events/power_system", 100);
00311   input_event_publisher  = nh.advertise < kobuki_msgs::DigitalInputEvent > ("events/digital_input", 100);
00312   robot_event_publisher  = nh.advertise < kobuki_msgs::RobotStateEvent > ("events/robot_state", 100, true); // also latched
00313   sensor_state_publisher = nh.advertise < kobuki_msgs::SensorState > ("sensors/core", 100);
00314   dock_ir_publisher = nh.advertise < kobuki_msgs::DockInfraRed > ("sensors/dock_ir", 100);
00315   imu_data_publisher = nh.advertise < sensor_msgs::Imu > ("sensors/imu_data", 100);
00316   raw_imu_data_publisher = nh.advertise < sensor_msgs::Imu > ("sensors/imu_data_raw", 100);
00317   raw_data_command_publisher = nh.advertise< std_msgs::String > ("debug/raw_data_command", 100);
00318   raw_data_stream_publisher = nh.advertise< std_msgs::String > ("debug/raw_data_stream", 100);
00319 }
00320 
00325 void KobukiRos::subscribeTopics(ros::NodeHandle& nh)
00326 {
00327   velocity_command_subscriber = nh.subscribe(std::string("commands/velocity"), 10, &KobukiRos::subscribeVelocityCommand, this);
00328   led1_command_subscriber =  nh.subscribe(std::string("commands/led1"), 10, &KobukiRos::subscribeLed1Command, this);
00329   led2_command_subscriber =  nh.subscribe(std::string("commands/led2"), 10, &KobukiRos::subscribeLed2Command, this);
00330   digital_output_command_subscriber =  nh.subscribe(std::string("commands/digital_output"), 10, &KobukiRos::subscribeDigitalOutputCommand, this);
00331   external_power_command_subscriber =  nh.subscribe(std::string("commands/external_power"), 10, &KobukiRos::subscribeExternalPowerCommand, this);
00332   sound_command_subscriber =  nh.subscribe(std::string("commands/sound"), 10, &KobukiRos::subscribeSoundCommand, this);
00333   reset_odometry_subscriber = nh.subscribe("commands/reset_odometry", 10, &KobukiRos::subscribeResetOdometry, this);
00334   motor_power_subscriber = nh.subscribe("commands/motor_power", 10, &KobukiRos::subscribeMotorPower, this);
00335 }
00336 
00337 
00338 } // namespace kobuki
00339 


kobuki_node
Author(s): Daniel Stonier , Younghun Ju , Jorge Santos Simon
autogenerated on Mon Oct 6 2014 01:32:48