00001 /************************************************************************************************** 00002 Software License Agreement (BSD License) 00003 00004 Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt 00005 All rights reserved. 00006 00007 Redistribution and use in source and binary forms, with or without modification, are permitted 00008 provided that the following conditions are met: 00009 00010 *Redistributions of source code must retain the above copyright notice, this list of 00011 conditions and the following disclaimer. 00012 *Redistributions in binary form must reproduce the above copyright notice, this list of 00013 conditions and the following disclaimer in the documentation and/or other materials provided 00014 with the distribution. 00015 *Neither the name of the University of Aveiro nor the names of its contributors may be used to 00016 endorse or promote products derived from this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR 00019 IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND 00020 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 00021 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00022 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00023 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER 00024 IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT 00025 OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 ***************************************************************************************************/ 00027 /* 00028 * Redistribution and use in source and binary forms, with or without 00029 * modification, are permitted provided that the following conditions 00030 * are met: 00031 * 1. Redistributions of source code must retain the above copyright 00032 * notice, this list of conditions and the following disclaimer. 00033 * 2. Redistributions in binary form must reproduce the above copyright 00034 * notice, this list of conditions and the following disclaimer in the 00035 * documentation and/or other materials provided with the distribution. 00036 * 3. Neither the name of Ricardo JS Pascoal nor the name of any other 00037 * contributor may be used to endorse or promote products derived 00038 * from this software without specific prior written permission. 00039 * 00040 * THIS SOFTWARE IS PROVIDED BY Ricardo JS Pascoal AND CONTRIBUTORS ``AS IS'' AND 00041 * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00042 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00043 * ARE DISCLAIMED. IN NO EVENT SHALL Ricardo JS Pascoal OR ANY OTHER 00044 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 00045 * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 00046 * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 00047 * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 00048 * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 00049 * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF 00050 * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00051 */ 00052 /* 00053 00054 */ 00055 00062 #ifndef _LASER_ROTATE3D_H_ 00063 #define _LASER_ROTATE3D_H_ 00064 00065 #define deg2rad 0.017453293 //change this to a standard ros function 00066 #define pulse2rad 0.003067962 // convert encoder pulses to radian 00067 #define deg2pulse 5.689 //2048/360 00068 00069 using namespace serialcom; 00070 00076 class RotateLaser: private SerialCom 00077 { 00078 00079 protected: 00080 ros::NodeHandle RotateLaser_nh; // the nodehandler associated with the rotation axis 00081 00082 private: 00083 /* http://drdobbs.com/cpp/184401518?pgno=2 00084 http://www.boost.org/doc/libs/1_37_0/doc/html/interprocess/synchronization_mechanisms.html 00085 don't allow the callback to access the variable while it is being used just before sending a message 00086 */ 00087 boost::mutex want2publish_mutex; 00088 00089 00090 // data to be transfered from the callback in the read thread to the publisher 00091 //std_msgs::String datatopublish; // change accordingly 00092 sensor_msgs::JointState joint_state; 00093 00094 int previous_position_request; 00095 int previous_speed_request; 00096 00097 // serial port specfic data 00098 int baud_rate_; 00099 std::string port_name_; 00100 00101 int sizeofcommand; 00102 char command2send[8]; //may be position or speed 00103 00104 // reference frame transformation 00105 tf::TransformBroadcaster TransfBroadcaster; 00106 tf::Transform Transform2Laser; 00107 00108 00109 00110 public: 00111 // ROS members 00112 //ros::ServiceServer set_speed_srv_, set_position_srv_, set_portandbaud_srv_; TODO use services 00113 ros::Publisher RotateLaser_pub; 00114 ros::Subscriber RotateLaser_sub; 00115 00116 //-------------- 00117 RotateLaser(); // opens the serial port to enable comm with PIC 00118 ~RotateLaser(); // sends the laser to the home position, stop, and closes the serial port 00119 bool SetPosition(int desiredposition); 00120 bool SetSpeed(int desiredrpm); 00121 bool SendCommand(); // send what is in command2send to the PIC 00122 void SetJointState(const sensor_msgs::JointState::ConstPtr& set_joint_state); 00123 boost::function<void(std::string*)> BoostRotateLaserCallback; 00124 void ReadLinesSerialPort(boost::function<void(std::string*)> f); 00125 void RotateLaserCallback(std::string* readdata); // callback to be used in the readline thread, 00126 //it will publish the information collected from the PIC 00127 void Publish(); // change this to make it adequate for the type of message 00128 00129 }; 00130 00136 RotateLaser:: ~RotateLaser() 00137 { 00138 stopStream(); //stop the thread, the SerialCom destructor will close it 00139 }; 00140 00146 // RotateLaser::RotateLaser() : RotateLaser_nh("~") // initial values for members 00147 RotateLaser::RotateLaser() : RotateLaser_nh("~") // initial values for members 00148 { 00149 //unlock the mutex 00150 // want2publish_mutex.unlock(); 00151 00152 /*default port name 00153 .param Assign value from parameter server, with default. */ 00154 RotateLaser_nh.param ("port", port_name_, std::string("/default")); 00155 RotateLaser_nh.param ("baud", baud_rate_, 115200); 00156 std::cout<<"Param port: "<<port_name_<<std::endl; 00157 00158 open(port_name_.c_str(),baud_rate_); //opens the serial port for reading and writing, inherited from SerialCom 00159 00160 // set initial to home position and zero speed 00161 previous_position_request = 0; 00162 previous_speed_request = 0; 00163 SetPosition(previous_position_request); //send to home 00164 00165 ROS_INFO("sent to home"); 00166 00167 joint_state.header.stamp = ros::Time::now(); 00168 // joint_state.set_name_size(1); 00169 joint_state.name.resize(1); 00170 // joint_state.set_position_size(1); 00171 joint_state.position.resize(1); 00172 // joint_state.set_velocity_size(1); 00173 joint_state.velocity.resize(1); 00174 00175 joint_state.name[0] =ros::names::remap("shaft"); 00176 joint_state.position[0] = -1; 00177 joint_state.velocity[0] = 0; 00178 00179 #if ROS_VERSION_MINIMUM(1, 8, 0) 00180 Transform2Laser.setOrigin(tf::Vector3(0,0, 0.0)); //nota estava Transform2Laser.setOrigin( tf::Vector3(0,-1, 0.0) ) 00181 Transform2Laser.setRotation(tf::Quaternion(0, 0, 0)); 00182 #else 00183 Transform2Laser.setOrigin(btVector3(0,0, 0.0)); //nota estava Transform2Laser.setOrigin( tf::Vector3(0,-1, 0.0) ) 00184 Transform2Laser.setRotation(btQuaternion(0, 0, 0)); 00185 #endif 00186 00187 // Transform2Laser.setOrigin(tf::Vector3(0,0, 0.0)); //nota estava Transform2Laser.setOrigin( tf::Vector3(0,-1, 0.0) ) 00188 // Transform2Laser.setRotation(tf::Quaternion(0, 0, 0)); 00189 00190 printf("remap=%s\n", (ros::names::remap("state")).c_str()); 00191 // publish the current angular position 00192 RotateLaser_pub = RotateLaser_nh.advertise<sensor_msgs::JointState>(ros::names::remap("state"),10); // this advertises the values 00193 //sensor_msgs::JointState std_msgs::String 00194 // subscribe a command 00195 RotateLaser_sub = RotateLaser_nh.subscribe<sensor_msgs::JointState>("cmd",1,&RotateLaser::SetJointState,this); 00196 //name, qeue, object member, object type 00197 00198 //service to set the serial port and baud rate 00199 // set_portandbaud_srv_ = RotateLaser_nh.advertiseService ("port", &RotateLaser::Set, this); TODO make this possible by changing the serial port class 00200 //service set speed 00201 //set_speed_srv_ = RotateLaser_nh.advertiseService ("speed", &RotateLaser::SetSpeed, this); 00202 //service set position 00203 //set_position_srv_ = RotateLaser_nh.advertiseService ("position", &RotateLaser::SetPosition, this); 00204 00205 00206 }; 00207 00215 void RotateLaser::SetJointState(const sensor_msgs::JointState::ConstPtr& set_joint_state) 00216 { 00217 00218 /* it is not possible to request speed and position simultaneously 00219 check which request has changed and make that one the active 00220 In case both change, give priority to speed requests. 00221 */ 00222 00223 if (set_joint_state->velocity.size()==0) 00224 { 00225 ROS_WARN("LASER3D VELOCITY REQUEST 0"); 00226 int position_request = (int)set_joint_state->position[0]; 00227 int speed_request = (int)set_joint_state->velocity[0]; 00228 //if(position_request != previous_position_request) 00229 { 00230 SetPosition((position_request*180./3.14)); 00231 ROS_INFO("Setting a new position"); 00232 previous_position_request = position_request; 00233 } 00234 } 00235 else 00236 { 00237 int position_request = (int)set_joint_state->position[0]; 00238 int speed_request = (int)set_joint_state->velocity[0]; 00239 SetSpeed(speed_request); 00240 ROS_INFO("Setting a new speed"); 00241 previous_speed_request = speed_request; 00242 previous_position_request = position_request; 00243 } 00244 00245 }; 00246 00251 bool RotateLaser::SetPosition(int desiredposition) 00252 { 00253 //send a command that sets the position of the laser 00254 //position is in degrees 00255 if ((desiredposition>359) | (desiredposition<0)) 00256 { 00257 ROS_WARN("Demanded position is in integer degrees range {0,...,359}."); 00258 return false; 00259 } 00260 00261 if(desiredposition==0) 00262 { 00263 command2send[0] = 'h'; // go to home 00264 command2send[1] = '\r'; 00265 sizeofcommand = 2; 00266 // sendthecommand 00267 return SendCommand(); 00268 }; 00269 00270 // common part of the command 00271 command2send[0] = 'v'; 00272 command2send[1] = '1'; 00273 command2send[2] = 'p'; //position 00274 00275 desiredposition = round(desiredposition*deg2pulse); // PIC is expecting pulse count 00276 00277 //itoa(desiredposition,command2send[3],10); //this is a nonstandard function 00278 sprintf(command2send+3,"%d",desiredposition); 00279 sizeofcommand = strlen(command2send); 00280 //ROS_INFO("position command received : %s", command2send); 00281 command2send[sizeofcommand] = '\r'; 00282 sizeofcommand+=1; 00283 00284 return SendCommand(); 00285 } 00286 00287 00292 bool RotateLaser::SetSpeed(int desiredrpm) 00293 { 00294 //send a command that sets the angular rate of the laser RPM. 00295 if ((desiredrpm>19) & (desiredrpm<100)) 00296 { 00297 command2send[0] = 'v'; 00298 command2send[1] = '1'; 00299 command2send[2] = 's'; 00300 command2send[3] = (desiredrpm - desiredrpm%10)/10 + 48; 00301 command2send[4] = desiredrpm%10 + 48; // 48 is the ascii value for 0 00302 command2send[5] = '\r'; 00303 sizeofcommand = 6; 00304 return (SendCommand()); 00305 } 00306 else 00307 { 00308 ROS_WARN("Demanded speed is in integer rpm range {20,...,99}."); 00309 return false; 00310 }; 00311 00312 } 00313 00318 bool RotateLaser::SendCommand() 00319 { 00320 00321 if(write(command2send,sizeofcommand)<sizeofcommand) 00322 { 00323 ROS_WARN ("Error writing the command!"); 00324 return false; 00325 } 00326 else 00327 { 00328 return true; 00329 } 00330 }; 00331 00336 void RotateLaser::ReadLinesSerialPort(boost::function<void(std::string*)> f) 00337 { 00338 startReadLineStream(f); //start a stream (thread) for reading from the serial port, inherited from SerialCom 00339 }; 00340 00345 void RotateLaser::Publish() //publish data safely 00346 { 00347 00348 if(want2publish_mutex.try_lock()) 00349 { 00350 // also lock in the callback for reading the serial port 00351 // it is safe to do whatever is needed with msg 00352 //ROS_INFO("safe publishing %s \n", "main thread");//readdata->c_str); 00353 if(joint_state.position[0]>=0) //it is initialized with -1 00354 { 00355 // publish the position as a change in a joint_state 00356 RotateLaser_pub.publish(joint_state); 00357 // publish the position as a change in reference frame 00358 00359 #if ROS_VERSION_MINIMUM(1, 8, 0) 00360 Transform2Laser.setOrigin( tf::Vector3(0,0.0, 0.0) ); //nota estava Transform2Laser.setOrigin( tf::Vector3(0,-1, 0.0) ) 00361 #else 00362 Transform2Laser.setOrigin(btVector3(0.0,0.0, 0.0)); //nota estava Transform2Laser.setOrigin( tf::Vector3(0,-1, 0.0) ) 00363 #endif 00364 00365 // Transform2Laser.setOrigin( tf::Vector3(1,0, 0.0) ); //nota estava Transform2Laser.setOrigin( tf::Vector3(0,-1, 0.0) ) 00366 00367 Transform2Laser.setRotation( tf::createQuaternionFromRPY(joint_state.position[0], 0, 0) ); 00368 // TransfBroadcaster.sendTransform(tf::StampedTransform(Transform2Laser, joint_state.header.stamp, "/atc/laser/roof_rotating", "/atc/laser/roof_rotating/base")); 00369 TransfBroadcaster.sendTransform(tf::StampedTransform(Transform2Laser, joint_state.header.stamp, "/atc/laser/roof_rotating/base", "/atc/laser/roof_rotating")); 00370 00371 want2publish_mutex.unlock(); 00372 // ROS_INFO("publishing %s\n",""); 00373 } 00374 else 00375 { 00376 ROS_INFO("no data available to publish %s\n",""); 00377 want2publish_mutex.unlock(); 00378 } 00379 } 00380 }; 00381 00382 00383 void RotateLaser::RotateLaserCallback(std::string* readdata) 00384 // this function is called back once the readline thread is invoked 00385 { 00386 int thesize; 00387 int aux; 00388 char Pos[1024]; 00389 char Vel[1024]; 00390 thesize = readdata->size(); 00391 00392 // for now print on screen what has been read 00393 00394 //ROS_INFO("In the rotatelaser callback"); 00395 00396 // if it is not locked then 00397 // have to pass the information in order to safely allow publishing 00398 // copy the message to a new variable and unlock 00399 // ROS_INFO("in callback string size %s \n", readdata->c_str());//readdata->c_str); 00400 00401 joint_state.header.stamp = ros::Time::now(); 00402 00403 // joint_state.position[0] = atof(readdata->c_str())*pulse2rad; 00404 //ROS_INFO("value read %f :", joint_state.position[0]); 00405 /*std::stringstream ss; 00406 ss << "collected in the callback"; 00407 datatopublish.data = ss.str();*/ 00408 00409 //get the posistion in the string P posistion V velocity 00410 aux=sscanf(readdata->c_str(),"%*c %s %*c %s\n",Pos,Vel); 00411 // ROS_INFO("value read: %s , atof: %f, converted: &f\n", Pos,atof(Pos),atof(Pos)*pulse2rad); 00412 // std::cout<<"value read: "<<Pos<<" atof: "<<atof(Pos)<<" converted: "<<atof(Pos)*pulse2rad<<std::endl; 00413 00414 want2publish_mutex.lock(); 00415 00416 joint_state.position[0] = atof(Pos)*pulse2rad; 00417 joint_state.velocity[0] = atof(Vel); 00418 want2publish_mutex.unlock(); 00419 usleep(10); 00420 00421 Publish(); //new change 2013 - 11 april 00422 }; 00423 00424 00425 #endif //EOF