65 kobuki_msgs::SensorState state;
69 state.bumper = data.
bumper;
71 state.cliff = data.
cliff;
82 state.bottom = cliff_data.
bottom;
85 state.current = current_data.
current;
87 GpInput::Data gp_input_data =
kobuki.getGpInputData();
88 state.digital_input = gp_input_data.digital_input;
89 for (
unsigned int i = 0; i < gp_input_data.analog_input.size(); ++i ) {
90 state.analog_input.push_back(gp_input_data.analog_input[i]);
102 ecl::linear_algebra::Vector3d pose_update_rates;
103 kobuki.updateOdometry(pose_update, pose_update_rates);
124 sensor_msgs::ImuPtr
msg(
new sensor_msgs::Imu);
126 msg->header.frame_id =
"gyro_link";
134 msg->orientation_covariance[0] = DBL_MAX;
135 msg->orientation_covariance[4] = DBL_MAX;
136 msg->orientation_covariance[8] = 0.05;
139 msg->angular_velocity.z =
kobuki.getAngularVelocity();
143 msg->angular_velocity_covariance[0] = DBL_MAX;
144 msg->angular_velocity_covariance[4] = DBL_MAX;
145 msg->angular_velocity_covariance[8] = 0.05;
157 sensor_msgs::ImuPtr
msg(
new sensor_msgs::Imu);
158 ThreeAxisGyro::Data
data =
kobuki.getRawInertiaData();
162 const double digit_to_dps = 0.00875;
163 unsigned int length = data.followed_data_length/3;
164 for(
unsigned int i=0; i<length; i++) {
167 msg->header.frame_id =
"gyro_link";
172 msg->header.stamp = now - interval * (length-i-1);
193 kobuki_msgs::DockInfraRedPtr
msg(
new kobuki_msgs::DockInfraRed);
195 msg->header.frame_id =
"dock_ir_link";
198 msg->data.push_back( data.docking[0] );
199 msg->data.push_back( data.docking[1] );
200 msg->data.push_back( data.docking[2] );
220 kobuki_msgs::VersionInfoPtr
msg(
new kobuki_msgs::VersionInfo);
227 msg->udid[0] = version_info.
udid0;
228 msg->udid[1] = version_info.
udid1;
229 msg->udid[2] = version_info.
udid2;
234 msg->features |= kobuki_msgs::VersionInfo::SMOOTH_MOVE_START;
235 msg->features |= kobuki_msgs::VersionInfo::GYROSCOPE_3D_DATA;
251 kobuki_msgs::ControllerInfoPtr
msg(
new kobuki_msgs::ControllerInfo);
254 msg->type = data.
type;
255 msg->p_gain =
static_cast<float>(data.
p_gain) * 0.001
f;;
256 msg->i_gain =
static_cast<float>(data.
i_gain) * 0.001
f;;
257 msg->d_gain =
static_cast<float>(data.
d_gain) * 0.001
f;;
271 kobuki_msgs::ButtonEventPtr
msg(
new kobuki_msgs::ButtonEvent);
272 switch(event.
state) {
291 kobuki_msgs::BumperEventPtr
msg(
new kobuki_msgs::BumperEvent);
292 switch(event.
state) {
298 case(
BumperEvent::Left) : { msg->bumper = kobuki_msgs::BumperEvent::LEFT;
break; }
311 kobuki_msgs::CliffEventPtr
msg(
new kobuki_msgs::CliffEvent);
312 switch(event.
state) {
313 case(
CliffEvent::Floor) : { msg->state = kobuki_msgs::CliffEvent::FLOOR;
break; }
314 case(
CliffEvent::Cliff) : { msg->state = kobuki_msgs::CliffEvent::CLIFF;
break; }
318 case(
CliffEvent::Left) : { msg->sensor = kobuki_msgs::CliffEvent::LEFT;
break; }
320 case(
CliffEvent::Right) : { msg->sensor = kobuki_msgs::CliffEvent::RIGHT;
break; }
323 msg->bottom =
event.bottom;
332 kobuki_msgs::WheelDropEventPtr
msg(
new kobuki_msgs::WheelDropEvent);
333 switch(event.
state) {
335 case(
WheelEvent::Raised) : { msg->state = kobuki_msgs::WheelDropEvent::RAISED;
break; }
338 switch(event.
wheel) {
339 case(
WheelEvent::Left) : { msg->wheel = kobuki_msgs::WheelDropEvent::LEFT;
break; }
340 case(
WheelEvent::Right) : { msg->wheel = kobuki_msgs::WheelDropEvent::RIGHT;
break; }
351 kobuki_msgs::PowerSystemEventPtr
msg(
new kobuki_msgs::PowerSystemEvent);
352 switch(event.
event) {
354 { msg->event = kobuki_msgs::PowerSystemEvent::UNPLUGGED;
break; }
356 { msg->event = kobuki_msgs::PowerSystemEvent::PLUGGED_TO_ADAPTER;
break; }
358 { msg->event = kobuki_msgs::PowerSystemEvent::PLUGGED_TO_DOCKBASE;
break; }
360 { msg->event = kobuki_msgs::PowerSystemEvent::CHARGE_COMPLETED;
break; }
362 { msg->event = kobuki_msgs::PowerSystemEvent::BATTERY_LOW;
break; }
364 { msg->event = kobuki_msgs::PowerSystemEvent::BATTERY_CRITICAL;
break; }
375 kobuki_msgs::DigitalInputEventPtr
msg(
new kobuki_msgs::DigitalInputEvent);
376 for (
unsigned int i = 0; i < msg->values.size(); i++)
377 msg->values[i] = event.
values[i];
386 kobuki_msgs::RobotStateEventPtr
msg(
new kobuki_msgs::RobotStateEvent);
387 switch(event.
state) {
388 case(
RobotEvent::Online) : { msg->state = kobuki_msgs::RobotStateEvent::ONLINE;
break; }
413 std::ostringstream ostream;
415 ostream << format(buffer);
417 s.data = ostream.str();
455 std::ostringstream ostream;
457 ostream << std::setfill(
'0') << std::uppercase;
458 for (
unsigned int i=0; i < buffer.
size(); i++)
459 ostream << std::hex << std::setw(2) <<
static_cast<unsigned int>(buffer[i]) <<
" " << std::dec;
462 std_msgs::StringPtr
msg(
new std_msgs::String);
463 msg->data = ostream.str();
475 std_msgs::Int16MultiArrayPtr
msg(
new std_msgs::Int16MultiArray);
476 msg->data = velocity_commands;
void publishPowerEvent(const PowerEvent &event)
ros::Publisher wheel_event_publisher
void publish(const boost::shared_ptr< M > &message) const
void publishWheelEvent(const WheelEvent &event)
ros::Publisher robot_event_publisher
unsigned int size() const
std::vector< uint8_t > current
ros::Publisher raw_imu_data_publisher
ros::Publisher version_info_publisher
void publishControllerInfo()
static std::string getSoftwareVersion()
std::vector< uint16_t > bottom
void publishButtonEvent(const ButtonEvent &event)
void publishInputEvent(const InputEvent &event)
sensor_msgs::JointState joint_states
enum kobuki::BumperEvent::Bumper bumper
ros::Publisher bumper_event_publisher
void publishCliffEvent(const CliffEvent &event)
void publishRobotEvent(const RobotEvent &event)
ros::Publisher cliff_event_publisher
ros::Publisher raw_data_stream_publisher
ros::Publisher controller_info_publisher
static std::string toString(const uint32_t &version)
ros::Publisher input_event_publisher
static double from_degrees(double degrees)
ros::Publisher imu_data_publisher
Wraps the kobuki driver in a ROS-specific library.
void publishRawDataStream(PacketFinder::BufferType &buffer)
Prints the raw data stream to a publisher.
void update(const ecl::LegacyPose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates, double imu_heading, double imu_angular_velocity)
ros::Publisher sensor_state_publisher
enum kobuki::PowerEvent::Event event
enum kobuki::WheelEvent::Wheel wheel
ros::Publisher raw_data_command_publisher
enum kobuki::RobotEvent::State state
void publishBumperEvent(const BumperEvent &event)
enum kobuki::WheelEvent::State state
void publishRawDataCommand(Command::Buffer &buffer)
Prints the raw data stream to a publisher.
void publishVersionInfo(const VersionInfo &version_info)
Publish fw, hw, sw version information.
enum kobuki::CliffEvent::Sensor sensor
uint32_t getNumSubscribers() const
void publishSensorState()
ros::Publisher power_event_publisher
ros::Publisher joint_state_publisher
enum kobuki::CliffEvent::State state
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
ros::Publisher dock_ir_publisher
ros::Publisher raw_control_command_publisher
enum kobuki::BumperEvent::State state
void publishRawControlCommand(const std::vector< short > &velocity_commands)
ros::Publisher button_event_publisher