afma6.cpp
Go to the documentation of this file.
1 #include <math.h>
2 #include <sstream>
3 #include <stdio.h>
4 
5 #include <geometry_msgs/Pose.h>
6 #include <geometry_msgs/PoseStamped.h>
7 #include <geometry_msgs/TwistStamped.h>
8 #include <nav_msgs/Odometry.h>
9 #include <ros/ros.h>
10 #include <tf/tf.h>
12 #include <tf/transform_datatypes.h>
13 #include <tf/transform_listener.h>
14 
15 #include <visp/vpRobotAfma6.h> // visp
16 
17 #include <visp_bridge/3dpose.h> // visp_bridge
18 
19 #ifdef VISP_HAVE_AFMA6
20 
22 {
23 public:
24  RosAfma6Node();
25  virtual ~RosAfma6Node();
26 
27 public:
28  int setup();
29  void setCameraVel( const geometry_msgs::TwistStampedConstPtr & );
30  void spin();
31  void publish();
32 
33 protected:
38 
40 
41  std::string m_serial_port;
42 
43  vpRobotAfma6 *m_robot;
44  geometry_msgs::PoseStamped m_position;
45 
46  // for odom->base_link transform
48  geometry_msgs::TransformStamped m_odom_trans;
49  // for resolving tf names.
50  std::string m_tf_prefix;
51  std::string m_frame_id_odom;
52  std::string m_frame_id_base_link;
53 
54  vpHomogeneousMatrix m_wMc; // world to camera transformation
55  vpColVector m_q; // measured joint position
56 
57  int m_tool_type = 0; // See https://visp-doc.inria.fr/doxygen/visp-daily/classvpAfma6.html structure vpAfma6ToolType
58 };
59 
61 {
62  ROS_INFO( "Using Afma6 robot" );
63 
64  m_robot = NULL;
65  /*
66  * Figure out what frame_id's to use. if a tf_prefix param is specified,
67  * it will be added to the beginning of the frame_ids.
68  *
69  * e.g. rosrun ... _tf_prefix:=MyRobot (or equivalently using <param>s in
70  * roslaunch files)
71  * will result in the frame_ids being set to /MyRobot/odom etc,
72  * rather than /odom. This is useful for Multi Robot Systems.
73  * See ROS Wiki for further details.
74  */
76  // m_frame_id_odom = tf::resolve(tf_prefix, "odom");
77  // m_frame_id_base_link = tf::resolve(tf_prefix, "base_link");
78 
79  m_nh.getParam( "tool_type", m_tool_type );
80 
81  // advertise services
82  m_pose_pub = m_nh.advertise< geometry_msgs::PoseStamped >( "pose", 1000 );
83  m_vel_pub = m_nh.advertise< geometry_msgs::TwistStamped >( "velocity", 1000 );
84 
85  // subscribe to services
87  m_nh.subscribe( "cmd_camvel", 1,
88  (boost::function< void( const geometry_msgs::TwistStampedConstPtr & ) >)boost::bind(
89  &RosAfma6Node::setCameraVel, this, _1 ) );
90 }
91 
93 {
94  if ( m_robot )
95  {
96  m_robot->stopMotion();
97  delete m_robot;
98  m_robot = NULL;
99  }
100 }
101 
102 int
104 {
105  m_robot = new vpRobotAfma6;
106 
107  m_robot->init( static_cast< vpAfma6::vpAfma6ToolType >( m_tool_type ), vpCameraParameters::perspectiveProjWithDistortion );
108  vpCameraParameters cam;
109  m_robot->getCameraParameters( cam, 640, 480 );
110  std::cout << "Camera parameters (640 x 480):\n" << cam << std::endl;
111 
112  m_robot->setRobotState( vpRobot::STATE_VELOCITY_CONTROL );
113 
114  return 0;
115 }
116 
117 void
119 {
120  ros::Rate loop_rate( 100 );
121  while ( ros::ok() )
122  {
123  this->publish();
124  ros::spinOnce();
125  loop_rate.sleep();
126  }
127  // ros::spin();
128 }
129 
130 void
132 {
133  double timestamp;
134  m_robot->getPosition( vpRobot::ARTICULAR_FRAME, m_q, timestamp );
135  m_wMc = m_robot->get_fMc( m_q );
137  m_position.header.stamp = ros::Time( timestamp ); // to improve: should be the timestamp returned by getPosition()
138 
139  // ROS_INFO( "Afma6 publish pose at %f s: [%0.2f %0.2f %0.2f] - [%0.2f %0.2f %0.2f %0.2f]",
140  // m_position.header.stamp.toSec(),
141  // m_position.pose.position.x, m_position.pose.position.y, m_position.pose.position.z,
142  // m_position.pose.orientation.w, m_position.pose.orientation.x, m_position.pose.orientation.y,
143  // m_position.pose.orientation.z);
145 
146  vpColVector vel( 6 );
147  m_robot->getVelocity( vpRobot::CAMERA_FRAME, vel, timestamp );
148  geometry_msgs::TwistStamped vel_msg;
149  vel_msg.header.stamp = ros::Time( timestamp );
150  vel_msg.twist.linear.x = vel[0];
151  vel_msg.twist.linear.y = vel[1];
152  vel_msg.twist.linear.z = vel[2];
153  vel_msg.twist.angular.x = vel[3];
154  vel_msg.twist.angular.y = vel[4];
155  vel_msg.twist.angular.z = vel[5];
156  m_vel_pub.publish( vel_msg );
157 
158  // ros::Duration(1e-3).sleep();
159 }
160 
161 void
162 RosAfma6Node::setCameraVel( const geometry_msgs::TwistStampedConstPtr &msg )
163 {
165 
166  vpColVector vc( 6 ); // Vel in m/s and rad/s
167 
168  vc[0] = msg->twist.linear.x;
169  vc[1] = msg->twist.linear.y;
170  vc[2] = msg->twist.linear.z;
171 
172  vc[3] = msg->twist.angular.x;
173  vc[4] = msg->twist.angular.y;
174  vc[5] = msg->twist.angular.z;
175 
176  // ROS_INFO( "Afma6 new camera vel at %f s: [%0.2f %0.2f %0.2f] m/s [%0.2f %0.2f %0.2f] rad/s",
177  // m_veltime.toSec(),
178  // vc[0], vc[1], vc[2], vc[3], vc[4], vc[5]);
179  m_robot->setVelocity( vpRobot::CAMERA_FRAME, vc );
180 
181  // this->publish();
182 }
183 
184 #endif // #ifdef VISP_HAVE_AFMA6
185 
186 int
187 main( int argc, char **argv )
188 {
189 #ifdef VISP_HAVE_AFMA6
190  ros::init( argc, argv, "RosAfma6" );
191 
192  RosAfma6Node node;
193 
194  try {
195  if ( node.setup() != 0 )
196  {
197  printf( "Afma6 setup failed... \n" );
198  return -1;
199  }
200 
201  node.spin();
202  }
203  catch(const vpException &e)
204  {
205  std::cout << "Catch exception: " << e.getMessage() << std::endl;
206  }
207 
208  printf( "\nQuitting... \n" );
209 #else
210  printf( "This node is node available since ViSP was \nnot build with Afma6 robot support...\n" );
211 #endif
212  return 0;
213 }
RosAfma6Node::m_vel_pub
ros::Publisher m_vel_pub
Definition: afma6.cpp:36
RosAfma6Node::m_odom_trans
geometry_msgs::TransformStamped m_odom_trans
Definition: afma6.cpp:48
ros::Publisher
RosAfma6Node::m_veltime
ros::Time m_veltime
Definition: afma6.cpp:39
RosAfma6Node::m_wMc
vpHomogeneousMatrix m_wMc
Definition: afma6.cpp:54
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
RosAfma6Node::m_frame_id_odom
std::string m_frame_id_odom
Definition: afma6.cpp:51
RosAfma6Node::m_cmd_camvel_sub
ros::Subscriber m_cmd_camvel_sub
Definition: afma6.cpp:37
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
RosAfma6Node::m_frame_id_base_link
std::string m_frame_id_base_link
Definition: afma6.cpp:52
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
main
int main(int argc, char **argv)
Definition: afma6.cpp:187
transform_broadcaster.h
RosAfma6Node::publish
void publish()
Definition: afma6.cpp:131
tf::TransformBroadcaster
tf::getPrefixParam
std::string getPrefixParam(ros::NodeHandle &nh)
3dpose.h
RosAfma6Node::m_tool_type
int m_tool_type
Definition: afma6.cpp:57
RosAfma6Node::m_tf_prefix
std::string m_tf_prefix
Definition: afma6.cpp:50
RosAfma6Node::~RosAfma6Node
virtual ~RosAfma6Node()
Definition: afma6.cpp:92
RosAfma6Node::m_robot
vpRobotAfma6 * m_robot
Definition: afma6.cpp:43
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())
RosAfma6Node::m_serial_port
std::string m_serial_port
Definition: afma6.cpp:41
ros::Rate::sleep
bool sleep()
visp_bridge::toGeometryMsgsPose
geometry_msgs::Pose toGeometryMsgsPose(const vpHomogeneousMatrix &mat)
transform_listener.h
tf.h
RosAfma6Node
Definition: afma6.cpp:21
RosAfma6Node::m_pose_pub
ros::Publisher m_pose_pub
Definition: afma6.cpp:35
transform_datatypes.h
ros::Time
RosAfma6Node::m_position
geometry_msgs::PoseStamped m_position
Definition: afma6.cpp:44
RosAfma6Node::setCameraVel
void setCameraVel(const geometry_msgs::TwistStampedConstPtr &)
Definition: afma6.cpp:162
ros::Rate
RosAfma6Node::RosAfma6Node
RosAfma6Node()
Definition: afma6.cpp:60
RosAfma6Node::m_odom_broadcaster
tf::TransformBroadcaster m_odom_broadcaster
Definition: afma6.cpp:47
ROS_INFO
#define ROS_INFO(...)
RosAfma6Node::spin
void spin()
Definition: afma6.cpp:118
RosAfma6Node::setup
int setup()
Definition: afma6.cpp:103
RosAfma6Node::m_nh
ros::NodeHandle m_nh
Definition: afma6.cpp:34
ros::NodeHandle
ros::Subscriber
RosAfma6Node::m_q
vpColVector m_q
Definition: afma6.cpp:55
ros::Time::now
static Time now()


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