42 #include <kobuki_msgs/VersionInfo.h> 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),
78 slot_raw_data_command(&
KobukiRos::publishRawDataCommand, *this),
79 slot_raw_data_stream(&
KobukiRos::publishRawDataStream, *this),
80 slot_raw_control_command(&
KobukiRos::publishRawControlCommand, *this)
147 ROS_ERROR_STREAM(
"Kobuki : no device port given on the parameter server (e.g. /dev/ttyUSB0)[" <<
name <<
"].");
154 std::string robot_description, wheel_left_joint_name, wheel_right_joint_name;
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"));
160 if (!nh_pub.
getParam(
"robot_description", robot_description))
162 ROS_WARN(
"Kobuki : no robot description given on the parameter server");
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());
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());
193 ROS_INFO(
"Kobuki : driver going into loopback (simulation) mode.");
199 ROS_INFO_STREAM(
"Kobuki : driver running in normal (non-simulation) mode" <<
" [" <<
name <<
"].");
212 if ( !
kobuki.isAlive() ) {
250 if (
kobuki.isShutdown() )
260 kobuki.setBaseControl(0, 0);
262 ROS_WARN(
"Kobuki : Incoming velocity commands not received for more than %.2f seconds -> zero'ing velocity commands",
odometry.
timeout().
toSec());
270 bool is_alive =
kobuki.isAlive();
BatteryTask battery_diagnostics
ecl::Slot< const RobotEvent & > slot_robot_event
WheelDropTask wheel_diagnostics
ros::Publisher wheel_event_publisher
ecl::Slot< const std::string & > slot_info
void subscribeMotorPower(const kobuki_msgs::MotorPowerConstPtr msg)
void subscribeDigitalOutputCommand(const kobuki_msgs::DigitalOutputConstPtr)
const char * what() const
ecl::Slot< const std::vector< std::string > & > slot_named
ros::Publisher robot_event_publisher
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.
ecl::Slot< const ButtonEvent & > slot_button_event
void setHardwareID(const std::string &hwid)
void update(const bool &is_alive)
ros::Publisher raw_imu_data_publisher
ros::Publisher version_info_publisher
void add(const std::string &name, TaskFunction f)
void update(bool new_state)
ecl::Slot< const BumperEvent & > slot_bumper_event
ecl::Slot slot_stream_data
ecl::Slot< const PowerEvent & > slot_power_event
std::string sigslots_namespace
AnalogInputTask ainput_diagnostics
sensor_msgs::JointState joint_states
void init(ros::NodeHandle &nh, const std::string &name)
WallSensorTask bumper_diagnostics
void subscribeControllerInfoCommand(const kobuki_msgs::ControllerInfoConstPtr msg)
MotorCurrentTask motor_diagnostics
ecl::Slot< Command::Buffer & > slot_raw_data_command
void update(const uint8_t &new_status)
ros::Publisher bumper_event_publisher
void subscribeSoundCommand(const kobuki_msgs::SoundConstPtr)
Play a predefined sound (single sound or sound sequence)
ecl::Slot< PacketFinder::BufferType & > slot_raw_data_stream
void subscribeLed1Command(const kobuki_msgs::LedConstPtr)
ros::Publisher cliff_event_publisher
ros::Publisher raw_data_stream_publisher
ros::Publisher controller_info_publisher
void update(const uint8_t &new_status)
const ros::Duration & timeout() const
ecl::Slot< const std::string & > slot_warn
void update(const Battery &battery)
ros::Publisher input_event_publisher
ros::Publisher imu_data_publisher
void update(const std::vector< uint8_t > &new_values)
Wraps the kobuki driver in a ROS-specific library.
ros::Subscriber digital_output_command_subscriber
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
GyroSensorTask gyro_diagnostics
WatchdogTask watchdog_diagnostics
ecl::Slot< const InputEvent & > slot_input_event
void subscribeExternalPowerCommand(const kobuki_msgs::ExternalPowerConstPtr)
ros::Publisher sensor_state_publisher
ecl::Slot< const VersionInfo & > slot_version_info
ros::Subscriber external_power_command_subscriber
ecl::Slot< const CliffEvent & > slot_cliff_event
void subscribeLed2Command(const kobuki_msgs::LedConstPtr)
ros::Subscriber controller_info_command_subscriber
ros::Subscriber velocity_command_subscriber
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool commandTimeout() const
MotorStateTask state_diagnostics
ros::Publisher raw_data_command_publisher
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
ros::Subscriber led2_command_subscriber
void connect(const std::string &topic)
DigitalInputTask dinput_diagnostics
bool init(ros::NodeHandle &nh, ros::NodeHandle &nh_pub)
#define ROS_INFO_STREAM(args)
ros::Subscriber led1_command_subscriber
ros::Publisher power_event_publisher
ros::Publisher joint_state_publisher
bool getParam(const std::string &key, std::string &s) const
void update(int16_t new_heading)
CliffSensorTask cliff_diagnostics
ros::Subscriber motor_power_subscriber
void advertiseTopics(ros::NodeHandle &nh)
ros::Publisher dock_ir_publisher
ros::Publisher raw_control_command_publisher
ros::Subscriber reset_odometry_subscriber
#define ROS_ERROR_STREAM(args)
void subscribeResetOdometry(const std_msgs::EmptyConstPtr)
Reset the odometry variables.
void subscribeTopics(ros::NodeHandle &nh)
ecl::Slot< const std::string & > slot_error
bool enable_acceleration_limiter
ecl::Slot< const std::string & > slot_debug
ros::Publisher button_event_publisher
void update(const uint8_t &new_status, const Cliff::Data &new_values)
diagnostic_updater::Updater updater
ecl::Slot< const std::vector< short > & > slot_raw_control_command
void subscribeVelocityCommand(const geometry_msgs::TwistConstPtr)
ros::Subscriber sound_command_subscriber
ecl::Slot< const WheelEvent & > slot_wheel_event
const ErrorFlag & flag() const
ecl::Slot slot_controller_info