Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00036
00037
00038
00039
00040 #ifndef KOBUKI_ROS_HPP_
00041 #define KOBUKI_ROS_HPP_
00042
00043
00044
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
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
00094
00095 std::string name;
00096 Kobuki kobuki;
00097 sensor_msgs::JointState joint_states;
00098 Odometry odometry;
00099 bool cmd_vel_timed_out_;
00100 bool serial_timed_out_;
00101
00102
00103
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
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
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
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
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
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 }
00191
00192 #endif