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 ** Includes 00038 *****************************************************************************/ 00039 00040 #include "kobuki_node/kobuki_ros.hpp" 00041 00042 /***************************************************************************** 00043 ** Namespaces 00044 *****************************************************************************/ 00045 00046 namespace kobuki 00047 { 00048 00049 void KobukiRos::processStreamData() { 00050 publishWheelState(); 00051 publishSensorState(); 00052 publishDockIRData(); 00053 publishInertia(); 00054 publishRawInertia(); 00055 } 00056 00057 /***************************************************************************** 00058 ** Publish Sensor Stream Workers 00059 *****************************************************************************/ 00060 00061 void KobukiRos::publishSensorState() 00062 { 00063 if ( ros::ok() ) { 00064 if (sensor_state_publisher.getNumSubscribers() > 0) { 00065 kobuki_msgs::SensorState state; 00066 CoreSensors::Data data = kobuki.getCoreSensorData(); 00067 state.header.stamp = ros::Time::now(); 00068 state.time_stamp = data.time_stamp; // firmware time stamp 00069 state.bumper = data.bumper; 00070 state.wheel_drop = data.wheel_drop; 00071 state.cliff = data.cliff; 00072 state.left_encoder = data.left_encoder; 00073 state.right_encoder = data.right_encoder; 00074 state.left_pwm = data.left_pwm; 00075 state.right_pwm = data.right_pwm; 00076 state.buttons = data.buttons; 00077 state.charger = data.charger; 00078 state.battery = data.battery; 00079 state.over_current = data.over_current; 00080 00081 Cliff::Data cliff_data = kobuki.getCliffData(); 00082 state.bottom = cliff_data.bottom; 00083 00084 Current::Data current_data = kobuki.getCurrentData(); 00085 state.current = current_data.current; 00086 00087 GpInput::Data gp_input_data = kobuki.getGpInputData(); 00088 state.digital_input = gp_input_data.digital_input; 00089 for ( unsigned int i = 0; i < gp_input_data.analog_input.size(); ++i ) { 00090 state.analog_input.push_back(gp_input_data.analog_input[i]); 00091 } 00092 00093 sensor_state_publisher.publish(state); 00094 } 00095 } 00096 } 00097 00098 void KobukiRos::publishWheelState() 00099 { 00100 ecl::Pose2D<double> pose_update; 00101 ecl::linear_algebra::Vector3d pose_update_rates; 00102 kobuki.updateOdometry(pose_update, pose_update_rates); 00103 kobuki.getWheelJointStates(joint_states.position[0], joint_states.velocity[0], // left wheel 00104 joint_states.position[1], joint_states.velocity[1]); // right wheel 00105 00106 odometry.update(pose_update, pose_update_rates); 00107 00108 if (ros::ok()) 00109 { 00110 joint_states.header.stamp = ros::Time::now(); 00111 joint_state_publisher.publish(joint_states); 00112 } 00113 } 00114 00115 void KobukiRos::publishInertia() 00116 { 00117 if (ros::ok()) 00118 { 00119 if (imu_data_publisher.getNumSubscribers() > 0) 00120 { 00121 // Publish as shared pointer to leverage the nodelets' zero-copy pub/sub feature 00122 sensor_msgs::ImuPtr msg(new sensor_msgs::Imu); 00123 00124 msg->header.frame_id = "gyro_link"; 00125 msg->header.stamp = ros::Time::now(); 00126 00127 msg->orientation = tf::createQuaternionMsgFromRollPitchYaw(0.0, 0.0, kobuki.getHeading()); 00128 00129 // set a very large covariance on unused dimensions (pitch and roll); 00130 // set yaw covariance as very low, to make it dominate over the odometry heading 00131 // 1: fill once, as its always the same; 2: cannot get better estimation? 00132 msg->orientation_covariance[0] = DBL_MAX; 00133 msg->orientation_covariance[4] = DBL_MAX; 00134 msg->orientation_covariance[8] = 0.005; 00135 00136 // fill angular velocity; we ignore acceleration for now 00137 msg->angular_velocity.z = kobuki.getAngularVelocity(); 00138 00139 // angular velocity covariance; useless by now, but robot_pose_ekf's 00140 // roadmap claims that it will compute velocities in the future 00141 msg->angular_velocity_covariance[0] = DBL_MAX; 00142 msg->angular_velocity_covariance[4] = DBL_MAX; 00143 msg->angular_velocity_covariance[8] = 0.005; 00144 00145 imu_data_publisher.publish(msg); 00146 } 00147 } 00148 } 00149 00150 void KobukiRos::publishRawInertia() 00151 { 00152 if ( ros::ok() && (raw_imu_data_publisher.getNumSubscribers() > 0) ) 00153 { 00154 // Publish as shared pointer to leverage the nodelets' zero-copy pub/sub feature 00155 sensor_msgs::ImuPtr msg(new sensor_msgs::Imu); 00156 ThreeAxisGyro::Data data = kobuki.getRawInertiaData(); 00157 00158 ros::Time now = ros::Time::now(); 00159 ros::Duration interval(0.01); // Time interval between each sensor reading. 00160 const double digit_to_dps = 0.00875; // digit to deg/s ratio, comes from datasheet of 3d gyro[L3G4200D]. 00161 unsigned int length = data.followed_data_length/3; 00162 for( unsigned int i=0; i<length; i++) { 00163 // Each sensor reading has id, that circulate 0 to 255. 00164 //msg->header.frame_id = std::string("gyro_link_" + boost::lexical_cast<std::string>((unsigned int)data.frame_id+i)); 00165 msg->header.frame_id = "gyro_link"; 00166 00167 // Update rate of 3d gyro sensor is 100 Hz, but robot's update rate is 50 Hz. 00168 // So, here is some compensation. 00169 // See also https://github.com/yujinrobot/kobuki/issues/216 00170 msg->header.stamp = now - interval * (length-i-1); 00171 00172 // Sensing axis of 3d gyro is not match with robot. It is rotated 90 degree counterclockwise about z-axis. 00173 msg->angular_velocity.x = angles::from_degrees( -digit_to_dps * (short)data.data[i*3+1] ); 00174 msg->angular_velocity.y = angles::from_degrees( digit_to_dps * (short)data.data[i*3+0] ); 00175 msg->angular_velocity.z = angles::from_degrees( digit_to_dps * (short)data.data[i*3+2] ); 00176 00177 raw_imu_data_publisher.publish(msg); 00178 } 00179 } 00180 } 00181 00182 void KobukiRos::publishDockIRData() 00183 { 00184 if (ros::ok()) 00185 { 00186 if (dock_ir_publisher.getNumSubscribers() > 0) 00187 { 00188 DockIR::Data data = kobuki.getDockIRData(); 00189 00190 // Publish as shared pointer to leverage the nodelets' zero-copy pub/sub feature 00191 kobuki_msgs::DockInfraRedPtr msg(new kobuki_msgs::DockInfraRed); 00192 00193 msg->header.frame_id = "dock_ir_link"; 00194 msg->header.stamp = ros::Time::now(); 00195 00196 msg->data.push_back( data.docking[0] ); 00197 msg->data.push_back( data.docking[1] ); 00198 msg->data.push_back( data.docking[2] ); 00199 00200 dock_ir_publisher.publish(msg); 00201 } 00202 } 00203 } 00204 00205 /***************************************************************************** 00206 ** Non Default Stream Packets 00207 *****************************************************************************/ 00214 void KobukiRos::publishVersionInfo(const VersionInfo &version_info) 00215 { 00216 if (ros::ok()) 00217 { 00218 kobuki_msgs::VersionInfoPtr msg(new kobuki_msgs::VersionInfo); 00219 00220 msg->firmware = VersionInfo::toString(version_info.firmware); 00221 msg->hardware = VersionInfo::toString(version_info.hardware); 00222 msg->software = VersionInfo::getSoftwareVersion(); 00223 00224 msg->udid.resize(3); 00225 msg->udid[0] = version_info.udid0; 00226 msg->udid[1] = version_info.udid1; 00227 msg->udid[2] = version_info.udid2; 00228 00229 // Set available features mask depending on firmware and driver versions 00230 if (version_info.firmware > 65536) // 1.0.0 00231 { 00232 msg->features |= kobuki_msgs::VersionInfo::SMOOTH_MOVE_START; 00233 msg->features |= kobuki_msgs::VersionInfo::GYROSCOPE_3D_DATA; 00234 } 00235 if (version_info.firmware > 65792) // 1.1.0 00236 { 00237 // msg->features |= kobuki_msgs::VersionInfo::SOMETHING_JINCHA_FANCY; 00238 } 00239 // if (msg->firmware > ... 00240 00241 version_info_publisher.publish(msg); 00242 } 00243 } 00244 00245 /***************************************************************************** 00246 ** Events 00247 *****************************************************************************/ 00248 00249 void KobukiRos::publishButtonEvent(const ButtonEvent &event) 00250 { 00251 if (ros::ok()) 00252 { 00253 kobuki_msgs::ButtonEventPtr msg(new kobuki_msgs::ButtonEvent); 00254 switch(event.state) { 00255 case(ButtonEvent::Pressed) : { msg->state = kobuki_msgs::ButtonEvent::PRESSED; break; } 00256 case(ButtonEvent::Released) : { msg->state = kobuki_msgs::ButtonEvent::RELEASED; break; } 00257 default: break; 00258 } 00259 switch(event.button) { 00260 case(ButtonEvent::Button0) : { msg->button = kobuki_msgs::ButtonEvent::Button0; break; } 00261 case(ButtonEvent::Button1) : { msg->button = kobuki_msgs::ButtonEvent::Button1; break; } 00262 case(ButtonEvent::Button2) : { msg->button = kobuki_msgs::ButtonEvent::Button2; break; } 00263 default: break; 00264 } 00265 button_event_publisher.publish(msg); 00266 } 00267 } 00268 00269 void KobukiRos::publishBumperEvent(const BumperEvent &event) 00270 { 00271 if (ros::ok()) 00272 { 00273 kobuki_msgs::BumperEventPtr msg(new kobuki_msgs::BumperEvent); 00274 switch(event.state) { 00275 case(BumperEvent::Pressed) : { msg->state = kobuki_msgs::BumperEvent::PRESSED; break; } 00276 case(BumperEvent::Released) : { msg->state = kobuki_msgs::BumperEvent::RELEASED; break; } 00277 default: break; 00278 } 00279 switch(event.bumper) { 00280 case(BumperEvent::Left) : { msg->bumper = kobuki_msgs::BumperEvent::LEFT; break; } 00281 case(BumperEvent::Center) : { msg->bumper = kobuki_msgs::BumperEvent::CENTER; break; } 00282 case(BumperEvent::Right) : { msg->bumper = kobuki_msgs::BumperEvent::RIGHT; break; } 00283 default: break; 00284 } 00285 bumper_event_publisher.publish(msg); 00286 } 00287 } 00288 00289 void KobukiRos::publishCliffEvent(const CliffEvent &event) 00290 { 00291 if (ros::ok()) 00292 { 00293 kobuki_msgs::CliffEventPtr msg(new kobuki_msgs::CliffEvent); 00294 switch(event.state) { 00295 case(CliffEvent::Floor) : { msg->state = kobuki_msgs::CliffEvent::FLOOR; break; } 00296 case(CliffEvent::Cliff) : { msg->state = kobuki_msgs::CliffEvent::CLIFF; break; } 00297 default: break; 00298 } 00299 switch(event.sensor) { 00300 case(CliffEvent::Left) : { msg->sensor = kobuki_msgs::CliffEvent::LEFT; break; } 00301 case(CliffEvent::Center) : { msg->sensor = kobuki_msgs::CliffEvent::CENTER; break; } 00302 case(CliffEvent::Right) : { msg->sensor = kobuki_msgs::CliffEvent::RIGHT; break; } 00303 default: break; 00304 } 00305 msg->bottom = event.bottom; 00306 cliff_event_publisher.publish(msg); 00307 } 00308 } 00309 00310 void KobukiRos::publishWheelEvent(const WheelEvent &event) 00311 { 00312 if (ros::ok()) 00313 { 00314 kobuki_msgs::WheelDropEventPtr msg(new kobuki_msgs::WheelDropEvent); 00315 switch(event.state) { 00316 case(WheelEvent::Dropped) : { msg->state = kobuki_msgs::WheelDropEvent::DROPPED; break; } 00317 case(WheelEvent::Raised) : { msg->state = kobuki_msgs::WheelDropEvent::RAISED; break; } 00318 default: break; 00319 } 00320 switch(event.wheel) { 00321 case(WheelEvent::Left) : { msg->wheel = kobuki_msgs::WheelDropEvent::LEFT; break; } 00322 case(WheelEvent::Right) : { msg->wheel = kobuki_msgs::WheelDropEvent::RIGHT; break; } 00323 default: break; 00324 } 00325 wheel_event_publisher.publish(msg); 00326 } 00327 } 00328 00329 void KobukiRos::publishPowerEvent(const PowerEvent &event) 00330 { 00331 if (ros::ok()) 00332 { 00333 kobuki_msgs::PowerSystemEventPtr msg(new kobuki_msgs::PowerSystemEvent); 00334 switch(event.event) { 00335 case(PowerEvent::Unplugged) : 00336 { msg->event = kobuki_msgs::PowerSystemEvent::UNPLUGGED; break; } 00337 case(PowerEvent::PluggedToAdapter) : 00338 { msg->event = kobuki_msgs::PowerSystemEvent::PLUGGED_TO_ADAPTER; break; } 00339 case(PowerEvent::PluggedToDockbase) : 00340 { msg->event = kobuki_msgs::PowerSystemEvent::PLUGGED_TO_DOCKBASE; break; } 00341 case(PowerEvent::ChargeCompleted) : 00342 { msg->event = kobuki_msgs::PowerSystemEvent::CHARGE_COMPLETED; break; } 00343 case(PowerEvent::BatteryLow) : 00344 { msg->event = kobuki_msgs::PowerSystemEvent::BATTERY_LOW; break; } 00345 case(PowerEvent::BatteryCritical) : 00346 { msg->event = kobuki_msgs::PowerSystemEvent::BATTERY_CRITICAL; break; } 00347 default: break; 00348 } 00349 power_event_publisher.publish(msg); 00350 } 00351 } 00352 00353 void KobukiRos::publishInputEvent(const InputEvent &event) 00354 { 00355 if (ros::ok()) 00356 { 00357 kobuki_msgs::DigitalInputEventPtr msg(new kobuki_msgs::DigitalInputEvent); 00358 for (unsigned int i = 0; i < msg->values.size(); i++) 00359 msg->values[i] = event.values[i]; 00360 input_event_publisher.publish(msg); 00361 } 00362 } 00363 00364 void KobukiRos::publishRobotEvent(const RobotEvent &event) 00365 { 00366 if (ros::ok()) 00367 { 00368 kobuki_msgs::RobotStateEventPtr msg(new kobuki_msgs::RobotStateEvent); 00369 switch(event.state) { 00370 case(RobotEvent::Online) : { msg->state = kobuki_msgs::RobotStateEvent::ONLINE; break; } 00371 case(RobotEvent::Offline) : { msg->state = kobuki_msgs::RobotStateEvent::OFFLINE; break; } 00372 default: break; 00373 } 00374 00375 robot_event_publisher.publish(msg); 00376 } 00377 } 00378 00392 void KobukiRos::publishRawDataCommand(Command::Buffer &buffer) 00393 { 00394 if ( raw_data_command_publisher.getNumSubscribers() > 0 ) { // do not do string processing if there is no-one listening. 00395 std::ostringstream ostream; 00396 Command::Buffer::Formatter format; 00397 ostream << format(buffer); // convert to an easily readable hex string. 00398 std_msgs::String s; 00399 s.data = ostream.str(); 00400 if (ros::ok()) 00401 { 00402 raw_data_command_publisher.publish(s); 00403 } 00404 } 00405 } 00419 void KobukiRos::publishRawDataStream(PacketFinder::BufferType &buffer) 00420 { 00421 if ( raw_data_stream_publisher.getNumSubscribers() > 0 ) { // do not do string processing if there is no-one listening. 00422 /*std::cout << "size: [" << buffer.size() << "], asize: [" << buffer.asize() << "]" << std::endl; 00423 std::cout << "leader: " << buffer.leader << ", follower: " << buffer.follower << std::endl; 00424 { 00425 std::ostringstream ostream; 00426 PacketFinder::BufferType::Formatter format; 00427 ostream << format(buffer); // convert to an easily readable hex string. 00428 //std::cout << ostream.str() << std::endl; 00429 std_msgs::String s; 00430 s.data = ostream.str(); 00431 if (ros::ok()) 00432 { 00433 raw_data_stream_publisher.publish(s); 00434 } 00435 }*/ 00436 { 00437 std::ostringstream ostream; 00438 ostream << "{ " ; 00439 ostream << std::setfill('0') << std::uppercase; 00440 for (unsigned int i=0; i < buffer.size(); i++) 00441 ostream << std::hex << std::setw(2) << static_cast<unsigned int>(buffer[i]) << " " << std::dec; 00442 ostream << "}"; 00443 //std::cout << ostream.str() << std::endl; 00444 std_msgs::StringPtr msg(new std_msgs::String); 00445 msg->data = ostream.str(); 00446 if (ros::ok()) 00447 { 00448 raw_data_stream_publisher.publish(msg); 00449 } 00450 } 00451 } 00452 } 00453 00454 } // namespace kobuki