kobuki_ros.hpp
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  */
00036 /*****************************************************************************
00037  ** Ifdefs
00038  *****************************************************************************/
00039 
00040 #ifndef KOBUKI_ROS_HPP_
00041 #define KOBUKI_ROS_HPP_
00042 
00043 /*****************************************************************************
00044  ** Includes
00045  *****************************************************************************/
00046 
00047 #include <string>
00048 #include <boost/shared_ptr.hpp>
00049 
00050 #include <ros/ros.h>
00051 #include <angles/angles.h>
00052 #include <std_msgs/Empty.h>
00053 #include <std_msgs/String.h>
00054 #include <sensor_msgs/JointState.h>
00055 #include <sensor_msgs/Imu.h>
00056 #include <ecl/sigslots.hpp>
00057 #include <kobuki_msgs/ButtonEvent.h>
00058 #include <kobuki_msgs/BumperEvent.h>
00059 #include <kobuki_msgs/CliffEvent.h>
00060 #include <kobuki_msgs/DigitalOutput.h>
00061 #include <kobuki_msgs/DigitalInputEvent.h>
00062 #include <kobuki_msgs/ExternalPower.h>
00063 #include <kobuki_msgs/DockInfraRed.h>
00064 #include <kobuki_msgs/Led.h>
00065 #include <kobuki_msgs/MotorPower.h>
00066 #include <kobuki_msgs/PowerSystemEvent.h>
00067 #include <kobuki_msgs/RobotStateEvent.h>
00068 #include <kobuki_msgs/SensorState.h>
00069 #include <kobuki_msgs/Sound.h>
00070 #include <kobuki_msgs/VersionInfo.h>
00071 #include <kobuki_msgs/WheelDropEvent.h>
00072 #include <kobuki_driver/kobuki.hpp>
00073 #include "diagnostics.hpp"
00074 #include "odometry.hpp"
00075 
00076 /*****************************************************************************
00077  ** Namespaces
00078  *****************************************************************************/
00079 
00080 namespace kobuki
00081 {
00082 class KobukiRos
00083 {
00084 public:
00085   KobukiRos(std::string& node_name);
00086   ~KobukiRos();
00087   bool init(ros::NodeHandle& nh);
00088   bool update();
00089 
00090   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00091 private:
00092   /*********************
00093    ** Variables
00094    **********************/
00095   std::string name; // name of the ROS node
00096   Kobuki kobuki;
00097   sensor_msgs::JointState joint_states;
00098   Odometry odometry;
00099   bool cmd_vel_timed_out_; // stops warning spam when cmd_vel flags as timed out more than once in a row
00100   bool serial_timed_out_; // stops warning spam when serial connection timed out more than once in a row
00101 
00102   /*********************
00103    ** Ros Comms
00104    **********************/
00105   ros::Publisher version_info_publisher;
00106   ros::Publisher imu_data_publisher, sensor_state_publisher, joint_state_publisher, dock_ir_publisher, raw_imu_data_publisher;
00107   ros::Publisher button_event_publisher, input_event_publisher, robot_event_publisher;
00108   ros::Publisher bumper_event_publisher, cliff_event_publisher, wheel_event_publisher, power_event_publisher;
00109   ros::Publisher raw_data_command_publisher, raw_data_stream_publisher;
00110 
00111   ros::Subscriber velocity_command_subscriber, digital_output_command_subscriber, external_power_command_subscriber;
00112   ros::Subscriber led1_command_subscriber, led2_command_subscriber, sound_command_subscriber;
00113   ros::Subscriber motor_power_subscriber, reset_odometry_subscriber;
00114 
00115   void advertiseTopics(ros::NodeHandle& nh);
00116   void subscribeTopics(ros::NodeHandle& nh);
00117 
00118   /*********************
00119   ** Ros Callbacks
00120   **********************/
00121   void subscribeVelocityCommand(const geometry_msgs::TwistConstPtr);
00122   void subscribeLed1Command(const kobuki_msgs::LedConstPtr);
00123   void subscribeLed2Command(const kobuki_msgs::LedConstPtr);
00124   void subscribeDigitalOutputCommand(const kobuki_msgs::DigitalOutputConstPtr);
00125   void subscribeExternalPowerCommand(const kobuki_msgs::ExternalPowerConstPtr);
00126   void subscribeResetOdometry(const std_msgs::EmptyConstPtr);
00127   void subscribeSoundCommand(const kobuki_msgs::SoundConstPtr);
00128   void subscribeMotorPower(const kobuki_msgs::MotorPowerConstPtr msg);
00129 
00130   /*********************
00131    ** SigSlots
00132    **********************/
00133   ecl::Slot<const VersionInfo&> slot_version_info;
00134   ecl::Slot<> slot_stream_data;
00135   ecl::Slot<const ButtonEvent&> slot_button_event;
00136   ecl::Slot<const BumperEvent&> slot_bumper_event;
00137   ecl::Slot<const CliffEvent&>  slot_cliff_event;
00138   ecl::Slot<const WheelEvent&>  slot_wheel_event;
00139   ecl::Slot<const PowerEvent&>  slot_power_event;
00140   ecl::Slot<const InputEvent&>  slot_input_event;
00141   ecl::Slot<const RobotEvent&>  slot_robot_event;
00142   ecl::Slot<const std::string&> slot_debug, slot_info, slot_warn, slot_error;
00143   ecl::Slot<Command::Buffer&> slot_raw_data_command;
00144   ecl::Slot<PacketFinder::BufferType&> slot_raw_data_stream;
00145 
00146   /*********************
00147    ** Slot Callbacks
00148    **********************/
00149   void processStreamData();
00150   void publishWheelState();
00151   void publishInertia();
00152   void publishRawInertia();
00153   void publishSensorState();
00154   void publishDockIRData();
00155   void publishVersionInfo(const VersionInfo &version_info);
00156   void publishButtonEvent(const ButtonEvent &event);
00157   void publishBumperEvent(const BumperEvent &event);
00158   void publishCliffEvent(const CliffEvent &event);
00159   void publishWheelEvent(const WheelEvent &event);
00160   void publishPowerEvent(const PowerEvent &event);
00161   void publishInputEvent(const InputEvent &event);
00162   void publishRobotEvent(const RobotEvent &event);
00163 
00164 
00165   // debugging
00166   void rosDebug(const std::string &msg) { ROS_DEBUG_STREAM("Kobuki : " << msg); }
00167   void rosInfo(const std::string &msg) { ROS_INFO_STREAM("Kobuki : " << msg); }
00168   void rosWarn(const std::string &msg) { ROS_WARN_STREAM("Kobuki : " << msg); }
00169   void rosError(const std::string &msg) { ROS_ERROR_STREAM("Kobuki : " << msg); }
00170 
00171   void publishRawDataCommand(Command::Buffer &buffer);
00172   void publishRawDataStream(PacketFinder::BufferType &buffer);
00173 
00174   /*********************
00175   ** Diagnostics
00176   **********************/
00177   diagnostic_updater::Updater updater;
00178   BatteryTask     battery_diagnostics;
00179   WatchdogTask   watchdog_diagnostics;
00180   CliffSensorTask   cliff_diagnostics;
00181   WallSensorTask   bumper_diagnostics;
00182   WheelDropTask     wheel_diagnostics;
00183   MotorCurrentTask  motor_diagnostics;
00184   MotorStateTask    state_diagnostics;
00185   GyroSensorTask     gyro_diagnostics;
00186   DigitalInputTask dinput_diagnostics;
00187   AnalogInputTask  ainput_diagnostics;
00188 };
00189 
00190 } // namespace kobuki
00191 
00192 #endif /* KOBUKI_ROS_HPP_ */


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