40 #include "../../include/kobuki_node/kobuki_ros.hpp" 61 ROS_DEBUG_STREAM(
"Kobuki : velocity command received [" << msg->linear.x <<
"],[" << msg->angular.z <<
"]");
62 kobuki.setBaseControl(msg->linear.x, msg->angular.z);
71 switch( msg->value ) {
76 default:
ROS_WARN_STREAM(
"Kobuki : led 1 command value invalid.");
break;
83 switch( msg->value ) {
88 default:
ROS_WARN_STREAM(
"Kobuki : led 2 command value invalid.");
break;
96 for (
unsigned int i = 0; i < 4; ++i ) {
97 digital_output.
values[i] = msg->values[i];
98 digital_output.
mask[i] = msg->mask[i];
100 kobuki.setDigitalOutput(digital_output);
107 if (!((msg->source == kobuki_msgs::ExternalPower::PWR_3_3V1A) ||
108 (msg->source == kobuki_msgs::ExternalPower::PWR_5V1A) ||
109 (msg->source == kobuki_msgs::ExternalPower::PWR_12V5A) ||
110 (msg->source == kobuki_msgs::ExternalPower::PWR_12V1_5A)))
112 ROS_ERROR_STREAM(
"Kobuki : Power source " << (
unsigned int)msg->source <<
" does not exist! [" <<
name <<
"].");
115 if (!((msg->state == kobuki_msgs::ExternalPower::OFF) ||
116 (msg->state == kobuki_msgs::ExternalPower::ON)))
119 << (
unsigned int)msg->state <<
" does not exist! [" <<
name <<
"].");
124 for (
unsigned int i = 0; i < 4; ++i )
126 if (i == msg->source)
130 digital_output.
values[i] =
true;
132 << (
unsigned int)msg->source <<
". [" <<
name <<
"].");
136 digital_output.
values[i] =
false;
138 << (
unsigned int)msg->source <<
". [" <<
name <<
"].");
140 digital_output.
mask[i] =
true;
144 digital_output.
values[i] =
false;
145 digital_output.
mask[i] =
false;
148 kobuki.setExternalPower(digital_output);
157 if ( msg->value == kobuki_msgs::Sound::ON )
161 else if ( msg->value == kobuki_msgs::Sound::OFF )
165 else if ( msg->value == kobuki_msgs::Sound::RECHARGE )
169 else if ( msg->value == kobuki_msgs::Sound::BUTTON )
173 else if ( msg->value == kobuki_msgs::Sound::ERROR )
177 else if ( msg->value == kobuki_msgs::Sound::CLEANINGSTART )
181 else if ( msg->value == kobuki_msgs::Sound::CLEANINGEND )
187 ROS_WARN_STREAM(
"Kobuki : Invalid sound command! There is no sound stored for value '" << msg->value <<
"'.");
209 if (msg->state == kobuki_msgs::MotorPower::ON)
215 else if (msg->state == kobuki_msgs::MotorPower::OFF)
223 ROS_ERROR_STREAM(
"Kobuki : Motor power command specifies unknown state '" << (
unsigned int)msg->state
224 <<
"'. [" <<
name <<
"]");
230 if( msg->p_gain < 0.0f || msg->i_gain < 0.0f || msg->d_gain < 0.0f) {
234 kobuki.setControllerGain(msg->type,
235 static_cast<unsigned int>(msg->p_gain*1000.0f),
236 static_cast<unsigned int>(msg->i_gain*1000.0f),
237 static_cast<unsigned int>(msg->d_gain*1000.0f));
void subscribeMotorPower(const kobuki_msgs::MotorPowerConstPtr msg)
void subscribeDigitalOutputCommand(const kobuki_msgs::DigitalOutputConstPtr)
sensor_msgs::JointState joint_states
void subscribeControllerInfoCommand(const kobuki_msgs::ControllerInfoConstPtr msg)
void subscribeSoundCommand(const kobuki_msgs::SoundConstPtr)
Play a predefined sound (single sound or sound sequence)
void subscribeLed1Command(const kobuki_msgs::LedConstPtr)
void subscribeExternalPowerCommand(const kobuki_msgs::ExternalPowerConstPtr)
void subscribeLed2Command(const kobuki_msgs::LedConstPtr)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
#define ROS_INFO_STREAM(args)
#define ROS_ERROR_STREAM(args)
void subscribeResetOdometry(const std_msgs::EmptyConstPtr)
Reset the odometry variables.
void subscribeVelocityCommand(const geometry_msgs::TwistConstPtr)