vpROSRobot.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * $Id: vpROSRobot.cpp 3530 2012-01-03 10:52:12Z fpasteau $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2012 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * vpRobot implementation for ROS middleware
36  *
37  * Authors:
38  * Francois Pasteau
39  *
40  *****************************************************************************/
41 
46 #include <iostream>
47 #include <sstream>
48 
49 #include <visp3/core/vpHomogeneousMatrix.h>
50 #include <visp3/robot/vpRobotException.h>
51 
52 #include <visp_ros/vpROSRobot.h>
53 
54 #include <ros/ros.h>
55 #include <ros/time.h>
56 
59  : isInitialized( false )
60  , odom_mutex( true )
61  , q( 0, 0, 0, 1 )
62  , p( 0, 0, 0 )
63  , _sec( 0 )
64  , _nsec( 0 )
65  , displacement( 6 )
66  , pose_prev( 6 )
67  , _master_uri( "http://127.0.0.1:11311" )
68  , _topic_cmd( "/RosAria/cmd_vel" )
69  , _topic_odom( "odom" )
70  , _nodespace( "" )
71 {
72 }
73 
76 {
77  if ( isInitialized )
78  {
79  isInitialized = false;
80  spinner->stop();
81  delete spinner;
82  delete n;
83  }
84 }
85 
91 void
92 vpROSRobot::init( int argc, char **argv )
93 {
94  if ( !isInitialized )
95  {
96  if ( !ros::isInitialized() )
97  ros::init( argc, argv, "visp_node", ros::init_options::AnonymousName );
98  n = new ros::NodeHandle;
99  cmdvel = n->advertise< geometry_msgs::Twist >( _nodespace + _topic_cmd, 1 );
102  spinner = new ros::AsyncSpinner( 1 );
103  spinner->start();
104  isInitialized = true;
105  }
106 }
107 
112 void
114 {
116  {
117  throw( vpRobotException( vpRobotException::constructionError,
118  "ROS robot already initialised with a different master_URI (" + ros::master::getURI() +
119  " != " + _master_uri + ")" ) );
120  }
121  if ( !isInitialized )
122  {
123  int argc = 2;
124  char *argv[2];
125  argv[0] = new char[255];
126  argv[1] = new char[255];
127 
128  std::string exe = "ros.exe", arg1 = "__master:=";
129  strcpy( argv[0], exe.c_str() );
130  arg1.append( _master_uri );
131  strcpy( argv[1], arg1.c_str() );
132  init( argc, argv );
133  delete[] argv[0];
134  delete[] argv[1];
135  }
136 }
137 
148 void
149 vpROSRobot::setVelocity( const vpRobot::vpControlFrameType frame, const vpColVector &vel )
150 {
151  geometry_msgs::Twist msg;
152  if ( frame == vpRobot::REFERENCE_FRAME )
153  {
154  msg.linear.x = vel[0];
155  msg.linear.y = vel[1];
156  msg.linear.z = vel[2];
157  msg.angular.x = vel[3];
158  msg.angular.y = vel[4];
159  msg.angular.z = vel[5];
160  cmdvel.publish( msg );
161  }
162  else
163  {
164  throw vpRobotException( vpRobotException::wrongStateError,
165  "Cannot send the robot velocity in the specified control frame" );
166  }
167 }
168 
179 void
180 vpROSRobot::getPosition( const vpRobot::vpControlFrameType frame, vpColVector &pose )
181 {
182  while ( !odom_mutex )
183  ;
184  odom_mutex = false;
185  if ( frame == vpRobot::REFERENCE_FRAME )
186  {
187  pose.resize( 6 );
188  pose[0] = p[0];
189  pose[1] = p[1];
190  pose[2] = p[2];
191  vpRotationMatrix R( q );
192  vpRxyzVector V( R );
193  pose[3] = V[0];
194  pose[4] = V[1];
195  pose[5] = V[2];
196  }
197  else
198  {
199  throw vpRobotException( vpRobotException::wrongStateError,
200  "Cannot get the robot position in the specified control frame" );
201  }
202  odom_mutex = true;
203 }
204 
218 void
219 vpROSRobot::getDisplacement( const vpRobot::vpControlFrameType frame, vpColVector &dis, struct timespec &timestamp )
220 {
221  while ( !odom_mutex )
222  ;
223  odom_mutex = false;
224  vpColVector pose_cur( displacement );
225  timestamp.tv_sec = _sec;
226  timestamp.tv_nsec = _nsec;
227  odom_mutex = true;
228  if ( frame == vpRobot::REFERENCE_FRAME )
229  {
230  dis = pose_cur - pose_prev;
231  pose_prev = pose_cur;
232  }
233  else
234  {
235  throw vpRobotException( vpRobotException::wrongStateError,
236  "Cannot get robot displacement in the specified control frame" );
237  }
238 }
239 
251 void
252 vpROSRobot::getDisplacement( const vpRobot::vpControlFrameType frame, vpColVector &dis )
253 {
254  struct timespec timestamp;
255  getDisplacement( frame, dis, timestamp );
256 }
257 
258 void
259 vpROSRobot::odomCallback( const nav_msgs::Odometry::ConstPtr &msg )
260 {
261  while ( !odom_mutex )
262  ;
263  odom_mutex = false;
264  p.set( msg->pose.pose.position.x, msg->pose.pose.position.y, msg->pose.pose.position.z );
265  q.set( msg->pose.pose.orientation.x, msg->pose.pose.orientation.y, msg->pose.pose.orientation.z,
266  msg->pose.pose.orientation.w );
267 
268  if ( _sec != 0 || _nsec != 0 )
269  {
270  double dt = ( (double)msg->header.stamp.sec - (double)_sec ) +
271  ( (double)msg->header.stamp.nsec - (double)_nsec ) / 1000000000.0;
272  displacement[0] += msg->twist.twist.linear.x * dt;
273  displacement[1] += msg->twist.twist.linear.y * dt;
274  displacement[2] += msg->twist.twist.linear.z * dt;
275  displacement[3] += msg->twist.twist.angular.x * dt;
276  displacement[4] += msg->twist.twist.angular.y * dt;
277  displacement[5] += msg->twist.twist.angular.z * dt;
278  }
279  _sec = msg->header.stamp.sec;
280  _nsec = msg->header.stamp.nsec;
281  odom_mutex = true;
282 }
283 
284 void
286 {
287  geometry_msgs::Twist msg;
288  msg.linear.x = 0;
289  msg.linear.y = 0;
290  msg.linear.z = 0;
291  msg.angular.x = 0;
292  msg.angular.y = 0;
293  msg.angular.z = 0;
294  cmdvel.publish( msg );
295 }
296 
304 void
305 vpROSRobot::setCmdVelTopic( std::string topic_name )
306 {
307  _topic_cmd = topic_name;
308 }
309 
317 void
318 vpROSRobot::setOdomTopic( std::string topic_name )
319 {
320  _topic_odom = topic_name;
321 }
322 
330 void
331 vpROSRobot::setMasterURI( std::string master_uri )
332 {
333  _master_uri = master_uri;
334 }
335 
343 void
344 vpROSRobot::setNodespace( std::string nodespace )
345 {
346  _nodespace = nodespace;
347 }
ros::init_options::AnonymousName
AnonymousName
vpROSRobot::setNodespace
void setNodespace(std::string nodespace)
Definition: vpROSRobot.cpp:344
vpROSRobot::displacement
vpColVector displacement
Definition: vpROSRobot.h:75
vpROSRobot::setOdomTopic
void setOdomTopic(std::string topic_name)
Definition: vpROSRobot.cpp:318
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
vpROSRobot::init
void init()
basic initialization
Definition: vpROSRobot.cpp:113
ros::AsyncSpinner::start
void start()
ros.h
time.h
vpROSRobot::getDisplacement
void getDisplacement(const vpRobot::vpControlFrameType, vpColVector &)
Definition: vpROSRobot.cpp:252
ros::AsyncSpinner
ros::TransportHints
vpQuaternionVector::set
void set(const double x, const double y, const double z, const double w)
vpROSRobot::_nodespace
std::string _nodespace
Definition: vpROSRobot.h:81
vpROSRobot::q
vpQuaternionVector q
Definition: vpROSRobot.h:72
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
vpROSRobot::setVelocity
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
Definition: vpROSRobot.cpp:149
ros::TransportHints::tcpNoDelay
TransportHints & tcpNoDelay(bool nodelay=true)
vpROSRobot::p
vpTranslationVector p
Definition: vpROSRobot.h:73
vpROSRobot::setMasterURI
void setMasterURI(std::string master_uri)
Definition: vpROSRobot.cpp:331
vpROSRobot::_master_uri
std::string _master_uri
Definition: vpROSRobot.h:78
vpROSRobot::_sec
uint32_t _sec
Definition: vpROSRobot.h:76
vpROSRobot::vpROSRobot
vpROSRobot()
constructor
Definition: vpROSRobot.cpp:58
vpROSRobot::_topic_cmd
std::string _topic_cmd
Definition: vpROSRobot.h:79
isInitialized
ROSCPP_DECL bool isInitialized()
vpROSRobot::pose_prev
vpColVector pose_prev
Definition: vpROSRobot.h:74
vpROSRobot::odomCallback
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: vpROSRobot.cpp:259
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
vpROSRobot::spinner
ros::AsyncSpinner * spinner
Definition: vpROSRobot.h:68
vpROSRobot::n
ros::NodeHandle * n
Definition: vpROSRobot.h:65
ros::AsyncSpinner::stop
void stop()
vpROSRobot::odom_mutex
volatile bool odom_mutex
Definition: vpROSRobot.h:77
vpROSRobot::setCmdVelTopic
void setCmdVelTopic(std::string topic_name)
Definition: vpROSRobot.cpp:305
vpROSRobot::getPosition
void getPosition(const vpRobot::vpControlFrameType, vpColVector &)
Definition: vpROSRobot.cpp:180
vpROSRobot::_topic_odom
std::string _topic_odom
Definition: vpROSRobot.h:80
vpROSRobot::stopMotion
void stopMotion()
Definition: vpROSRobot.cpp:285
vpROSRobot::_nsec
uint32_t _nsec
Definition: vpROSRobot.h:76
vpROSRobot.h
vpRobot implementation for ROS middleware.
vpROSRobot::~vpROSRobot
virtual ~vpROSRobot()
destructor
Definition: vpROSRobot.cpp:75
vpROSRobot::cmdvel
ros::Publisher cmdvel
Definition: vpROSRobot.h:66
vpROSRobot::odom
ros::Subscriber odom
Definition: vpROSRobot.h:67
ros::master::getURI
const ROSCPP_DECL std::string & getURI()
vpROSRobot::isInitialized
bool isInitialized
Definition: vpROSRobot.h:70
ros::NodeHandle


visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33