$search
00001 /* 00002 # ROS node to read Nao's sensors and torso odometry through the Aldebaran API. 00003 # This code is currently compatible to NaoQI version 1.6 00004 # 00005 # Copyright 2011 Daniel Maier, University of Freiburg 00006 # http://www.ros.org/wiki/nao 00007 # 00008 # Redistribution and use in source and binary forms, with or without 00009 # modification, are permitted provided that the following conditions are met: 00010 # 00011 # # Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # # Redistributions in binary form must reproduce the above copyright 00014 # notice, this list of conditions and the following disclaimer in the 00015 # documentation and/or other materials provided with the distribution. 00016 # # Neither the name of the University of Freiburg nor the names of its 00017 # contributors may be used to endorse or promote products derived from 00018 # this software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00021 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00022 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00023 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00024 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00025 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00026 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00027 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00028 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00029 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00030 # POSSIBILITY OF SUCH DAMAGE. 00031 */ 00032 00033 #include <ros/ros.h> 00034 #include <sensor_msgs/JointState.h> 00035 #include <nao_msgs/TorsoOdometry.h> 00036 #include <nao_msgs/TorsoIMU.h> 00037 #include <iostream> 00038 // Aldebaran includes 00039 #include <almemoryproxy.h> 00040 #include <almotionproxy.h> 00041 #include <alvisiondefinitions.h> 00042 #include <alerror.h> 00043 #include <alvalue.h> 00044 #include <altoolsmain.h> 00045 #include <alproxies/alvideodeviceproxy.h> 00046 #include <alcommon/albroker.h> 00047 #include <alcommon/albrokermanager.h> 00048 #include <alcommon/alproxy.h> 00049 #include <alproxies/alproxies.h> 00050 #include <alproxies/almotionproxy.h> 00051 #include <alproxies/almemoryproxy.h> 00052 #include <alcommon/almodule.h> 00053 #include <alcommon/albroker.h> 00054 #include <alcommon/albrokermanager.h> 00055 00056 00057 00058 // Other includes 00059 #include <boost/program_options.hpp> 00060 00061 using namespace std; 00062 /* 00063 from nao_driver import * 00064 00065 import threading 00066 from threading import Thread 00067 00068 */ 00069 class NaoNode 00070 { 00071 public: 00072 NaoNode(); 00073 ~NaoNode(); 00074 bool connectNaoQi(); 00075 void parse_command_line(int argc, char ** argv); 00076 protected: 00077 std::string m_pip; 00078 std::string m_ip; 00079 int m_port; 00080 int m_pport; 00081 std::string m_brokerName; 00082 boost::shared_ptr<AL::ALBroker> m_broker; 00083 00084 00085 }; 00086 00087 00088 NaoNode::NaoNode() : m_pip("127.0.0.01"),m_ip("0.0.0.0"),m_port(16712),m_pport(9559),m_brokerName("NaoROSBroker") 00089 { 00090 00091 00092 } 00093 00094 NaoNode::~NaoNode() 00095 { 00096 } 00097 00098 void NaoNode::parse_command_line(int argc, char ** argv) 00099 { 00100 std::string pip; 00101 std::string ip; 00102 int pport; 00103 int port; 00104 boost::program_options::options_description desc("Configuration"); 00105 desc.add_options() 00106 ("help", "show this help message") 00107 ("ip", boost::program_options::value<std::string>(&ip)->default_value(m_ip), 00108 "IP/hostname of the broker") 00109 ("port", boost::program_options::value<int>(&port)->default_value(m_port), 00110 "Port of the broker") 00111 ("pip", boost::program_options::value<std::string>(&pip)->default_value(m_pip), 00112 "IP/hostname of parent broker") 00113 ("pport", boost::program_options::value<int>(&pport)->default_value(m_pport), 00114 "port of parent broker") 00115 ; 00116 boost::program_options::variables_map vm; 00117 boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm); 00118 boost::program_options::notify(vm); 00119 m_port = vm["port"].as<int>(); 00120 m_pport = vm["pport"].as<int>(); 00121 m_pip = vm["pip"].as<std::string>(); 00122 m_ip = vm["ip"].as<std::string>(); 00123 cout << "pip is " << m_pip << endl; 00124 cout << "ip is " << m_ip << endl; 00125 cout << "port is " << m_port << endl; 00126 cout << "pport is " << m_pport << endl; 00127 00128 if (vm.count("help")) { 00129 std::cout << desc << "\n"; 00130 return ; 00131 } 00132 } 00133 00134 00135 00136 bool NaoNode::connectNaoQi() 00137 { 00138 // Need this to for SOAP serialization of floats to work 00139 setlocale(LC_NUMERIC, "C"); 00140 // A broker needs a name, an IP and a port: 00141 // FIXME: would be a good idea to look for a free port first 00142 // listen port of the broker (here an anything) 00143 try 00144 { 00145 m_broker = AL::ALBroker::createBroker(m_brokerName, m_ip, m_port, m_pip, m_pport, false); 00146 } 00147 catch(const AL::ALError& e) 00148 { 00149 ROS_ERROR( "Failed to connect broker to: %s:%d",m_pip.c_str(),m_port); 00150 //AL::ALBrokerManager::getInstance()->killAllBroker(); 00151 //AL::ALBrokerManager::kill(); 00152 return false; 00153 } 00154 cout << "broker ready." << endl; 00155 return true; 00156 } 00157 00158 class NaoSensors : public NaoNode 00159 { 00160 public: 00161 //NaoSensors() ; 00162 NaoSensors(int argc, char ** argv); 00163 ~NaoSensors(); 00164 00165 bool connectProxy(); 00166 void run(); 00167 protected: 00168 00169 double m_rate; 00170 boost::shared_ptr<AL::ALMotionProxy> m_motionProxy; 00171 boost::shared_ptr<AL::ALMemoryProxy> m_memoryProxy; 00172 AL::ALValue m_dataNamesList; 00173 ros::NodeHandle m_nh; 00174 ros::NodeHandle m_privateNh; 00175 bool m_send_cam_odom; 00176 std::string m_tf_prefix; 00177 std::string m_odom_frame_id; 00178 std::string m_base_frame_id; 00179 nao_msgs::TorsoOdometry m_torsoOdom; 00180 nao_msgs::TorsoOdometry m_camOdom; 00181 nao_msgs::TorsoIMU m_torsoIMU; 00182 sensor_msgs::JointState m_jointState; 00183 ros::Publisher m_torsoOdomPub; 00184 ros::Publisher m_camOdomPub; 00185 ros::Publisher m_torsoIMUPub; 00186 ros::Publisher m_jointStatePub; 00187 }; 00188 00189 bool NaoSensors::connectProxy() 00190 { 00191 if (!m_broker) 00192 { 00193 ROS_ERROR("Broker is not ready. Have you called connectNaoQi()?"); 00194 return false; 00195 } 00196 try 00197 { 00198 //m_motionProxy = boost::shared_ptr<AL::ALProxy>(m_broker->getProxy("ALMotion")); 00199 m_motionProxy = boost::shared_ptr<AL::ALMotionProxy>(new AL::ALMotionProxy(m_broker)); 00200 } 00201 catch (const AL::ALError& e) 00202 { 00203 ROS_ERROR("Could not create ALMotionProxy."); 00204 return false; 00205 } 00206 try 00207 { 00208 //m_memoryProxy = boost::shared_ptr<AL::ALMemoryProxy>(m_broker->getProxy("ALMemory")); 00209 m_memoryProxy = boost::shared_ptr<AL::ALMemoryProxy>(new AL::ALMemoryProxy(m_broker)); 00210 } 00211 catch (const AL::ALError& e) 00212 { 00213 ROS_ERROR("Could not create ALMemoryProxy."); 00214 return false; 00215 } 00216 ROS_INFO("Proxies to ALMotion and ALMemory ready."); 00217 return true; 00218 } 00219 00220 NaoSensors::NaoSensors(int argc, char ** argv) 00221 : m_rate(50.0), m_privateNh("~"), 00222 m_send_cam_odom(false), 00223 m_tf_prefix(""), 00224 m_odom_frame_id("odom"), 00225 m_base_frame_id("torso") 00226 { 00227 parse_command_line(argc,argv); 00228 if ( ! connectNaoQi() || ! connectProxy() ) 00229 { 00230 ROS_ERROR("Gosh! Throwsing exception"); 00231 throw std::exception(); 00232 } 00233 m_dataNamesList = AL::ALValue::array("DCM/Time", 00234 "Device/SubDeviceList/InertialSensor/AngleX/Sensor/Value","Device/SubDeviceList/InertialSensor/AngleY/Sensor/Value", 00235 "Device/SubDeviceList/InertialSensor/GyrX/Sensor/Value", "Device/SubDeviceList/InertialSensor/GyrY/Sensor/Value", 00236 "Device/SubDeviceList/InertialSensor/AccX/Sensor/Value", "Device/SubDeviceList/InertialSensor/AccY/Sensor/Value", 00237 "Device/SubDeviceList/InertialSensor/AccZ/Sensor/Value"); 00238 00239 00240 // get update frequency 00241 m_privateNh.param("torso_odom_rate", m_rate,m_rate); 00242 // get tf prefix 00243 std::string tf_prefix_param_name; 00244 if ( m_nh.searchParam("tf_prefix", tf_prefix_param_name) ) 00245 { 00246 m_nh.param(tf_prefix_param_name,m_tf_prefix,m_tf_prefix); 00247 } 00248 else 00249 { 00250 ROS_WARN("Could not find tf_prefix, using \"%s\" instead",m_tf_prefix.c_str()); 00251 } 00252 // get base_frame_id (and fix prefixi f necessary) 00253 m_privateNh.param("base_frame_id", m_base_frame_id, m_base_frame_id); 00254 if (m_base_frame_id[0] != '/') 00255 m_base_frame_id = m_tf_prefix + '/' + m_base_frame_id; 00256 00257 // check if we need to send camera odometry 00258 m_privateNh.param("send_cam_odom", m_send_cam_odom, m_send_cam_odom); 00259 // initialize messages 00260 /* 00261 m_torsoOdom = nao_msgs::TorsoOdometry; 00262 m_camOdom = nao_msgs::TorsoOdometry; 00263 m_torsoIMU = nao_msgs::TorsoIMU; 00264 m_jointState = nao_msgs::JointState; 00265 */ 00266 m_privateNh.param("odom_frame_id", m_odom_frame_id, m_odom_frame_id); 00267 if (m_odom_frame_id[0] != '/') 00268 { 00269 m_odom_frame_id = m_tf_prefix + '/' + m_odom_frame_id; 00270 } 00271 m_torsoOdom.header.frame_id = m_odom_frame_id; 00272 m_camOdom.header.frame_id = m_odom_frame_id; 00273 m_torsoIMU.header.frame_id = m_base_frame_id; 00274 m_jointState.name = m_motionProxy->getJointNames("Body"); 00275 00276 // simluated model misses some joints, we need to fill: 00277 if (m_jointState.name.size() == 22) 00278 { 00279 // TODO: Check this! 00280 m_jointState.name.insert(m_jointState.name.begin()+6,"LWristYaw"); 00281 m_jointState.name.insert(m_jointState.name.begin()+7,"LHand"); 00282 m_jointState.name.push_back("RWristYaw"); 00283 m_jointState.name.push_back("RHand"); 00284 } 00285 00286 std::stringstream ss; 00287 ss << "Nao joints found: " ; 00288 std::copy(m_jointState.name.begin(), m_jointState.name.end()-1, std::ostream_iterator<std::string>(ss,",")); 00289 std::copy(m_jointState.name.end()-1, m_jointState.name.end(), std::ostream_iterator<std::string>(ss)); 00290 ROS_INFO("Nao joints found: %s",ss.str().c_str()); 00291 00292 00293 if (m_send_cam_odom) 00294 m_camOdomPub = m_nh.advertise<nao_msgs::TorsoOdometry>("camera_odometry",5); 00295 m_torsoOdomPub = m_nh.advertise<nao_msgs::TorsoOdometry>("torso_odometry",5); 00296 m_torsoIMUPub = m_nh.advertise<nao_msgs::TorsoIMU>("torso_imu",5); 00297 m_jointStatePub = m_nh.advertise<sensor_msgs::JointState>("joint_states",5); 00298 00299 ROS_INFO("nao_sensors initialized"); 00300 00301 } 00302 NaoSensors::~NaoSensors() 00303 { 00304 } 00305 void NaoSensors::run() 00306 { 00307 ros::Rate r(m_rate); 00308 ros::Time stamp1; 00309 ros::Time stamp2; 00310 ros::Time stamp; 00311 std::vector<float> odomData; 00312 std::vector<float> camData; 00313 std::vector<float> memData; 00314 std::vector<float> positionData; 00315 ROS_INFO("Staring main loop. ros::ok() is %d nh.ok() is %d",ros::ok(),m_nh.ok()); 00316 while(ros::ok() ) 00317 { 00318 r.sleep(); 00319 ros::spinOnce(); 00320 stamp1 = ros::Time::now(); 00321 try 00322 { 00323 memData = m_memoryProxy->getListData(m_dataNamesList); 00324 // {SPACE_TORSO = 0, SPACE_WORLD = 1, SPACE_NAO = 2}. (second argument) 00325 odomData = m_motionProxy->getPosition("Torso", 1, true); 00326 if (m_send_cam_odom) 00327 camData = m_motionProxy->getPosition("CameraTop", 1, true); 00328 positionData = m_motionProxy->getAngles("Body", true); 00329 } 00330 catch (const AL::ALError & e) 00331 { 00332 ROS_ERROR( "Error accessing ALMemory, exiting..."); 00333 ROS_ERROR( "%s", e.what() ); 00334 //ros.signal_shutdown("No NaoQI available anymore"); 00335 } 00336 stamp2 = ros::Time::now(); 00337 //ROS_DEBUG("dt is %f",(stamp2-stamp1).toSec()); % dt is typically around 1/1000 sec 00338 // TODO: Something smarter than this.. 00339 stamp = stamp1 + ros::Duration((stamp2-stamp1).toSec()/2.0); 00340 00341 if (odomData.size()!=6) 00342 { 00343 ROS_ERROR( "Error getting odom data. length is %u",odomData.size() ); 00344 continue; 00345 } 00346 if (m_send_cam_odom && camData.size()!=6) 00347 { 00348 ROS_ERROR( "Error getting camera odom data. length is %u",camData.size() ); 00349 continue; 00350 } 00351 m_torsoOdom.header.stamp = stamp; 00352 m_torsoOdom.x = odomData[0]; 00353 m_torsoOdom.y = odomData[1]; 00354 m_torsoOdom.z = odomData[2]; 00355 m_torsoOdom.wx = odomData[3]; 00356 m_torsoOdom.wy = odomData[4]; 00357 m_torsoOdom.wz = odomData[5]; 00358 00359 if (m_send_cam_odom) 00360 { 00361 m_camOdom.header.stamp = stamp; 00362 m_camOdom.x = camData[0]; 00363 m_camOdom.y = camData[1]; 00364 m_camOdom.z = camData[2]; 00365 m_camOdom.wx = camData[3]; 00366 m_camOdom.wy = camData[4]; 00367 m_camOdom.wz = camData[5]; 00368 } 00369 00370 m_torsoOdomPub.publish(m_torsoOdom); 00371 if (m_send_cam_odom) 00372 m_camOdomPub.publish(m_camOdom); 00373 00374 // Replace 'None' values with 0 00375 // (=> consistent behavior in 1.8 / 1.10 with 1.6) 00376 // Should not be necessary because NULL==0, but I'll leave it here.. 00377 /* 00378 for (unsigned i = 0; i<memData.size(); ++i) 00379 { 00380 if (memData[i]==NULL) 00381 memData[i] = 0; 00382 } 00383 */ 00384 if (memData.size() != m_dataNamesList.getSize()) 00385 { 00386 ROS_ERROR("memData length %u does not match expected length %u",memData.size(),m_dataNamesList.getSize() ); 00387 continue; 00388 } 00389 // IMU data: 00390 m_torsoIMU.header.stamp = stamp; 00391 m_torsoIMU.angleX = memData[1]; 00392 m_torsoIMU.angleY = memData[2]; 00393 m_torsoIMU.gyroX = memData[3]; 00394 m_torsoIMU.gyroY = memData[4]; 00395 m_torsoIMU.accelX = memData[5]; 00396 m_torsoIMU.accelY = memData[6]; 00397 m_torsoIMU.accelZ = memData[7]; 00398 00399 m_torsoIMUPub.publish(m_torsoIMU); 00400 00401 // Joint States: 00402 m_jointState.header.stamp = stamp; 00403 m_jointState.header.frame_id = m_base_frame_id; 00404 m_jointState.position.resize(positionData.size()); 00405 for(unsigned i = 0; i<positionData.size(); ++i) 00406 { 00407 m_jointState.position[i] = positionData[i]; 00408 } 00409 00410 // simulated model misses some joints, we need to fill: 00411 if (m_jointState.position.size() == 22) 00412 { 00413 m_jointState.position.insert(m_jointState.position.begin()+6,0.0); 00414 m_jointState.position.insert(m_jointState.position.begin()+7,0.0); 00415 m_jointState.position.push_back(0.0); 00416 m_jointState.position.push_back(0.0); 00417 } 00418 00419 m_jointStatePub.publish(m_jointState); 00420 00421 } 00422 ROS_INFO("nao_sensors stopped."); 00423 00424 } 00425 00426 00427 int main(int argc, char ** argv) 00428 { 00429 ros::init(argc, argv, "nao_sensors_cpp"); 00430 cout << "I am here" << endl; 00431 NaoSensors * sensors; 00432 try{ 00433 sensors = new NaoSensors(argc,argv); 00434 //NaoSensors sensors(argc,argv); 00435 } 00436 catch (const std::exception & e) 00437 //catch (...) 00438 { 00439 // TODO: why does this not work? 00440 //ROS_ERROR("Creating NaoSensors object failed with error %s",e.what()); 00441 ROS_ERROR("Creating NaoSensors object failed with error "); 00442 return -1; 00443 } 00444 //sensors.parse_command_line(argc,argv); 00445 //sensors.connectNaoQi(); 00446 //sensors.connectProxy(); 00447 sensors->run(); 00448 delete sensors; 00449 00450 /* 00451 ROS_INFO("NodeHandle"); 00452 ros::Rate r(50); 00453 00454 while(ros::ok() ) 00455 { 00456 r.sleep(); 00457 ros::spinOnce(); 00458 } 00459 ROS_INFO("nao_sensors stopped."); 00460 */ 00461 ROS_INFO("End of the road."); 00462 return 0; 00463 }