biclops.cpp
Go to the documentation of this file.
1 #include <math.h>
2 #include <stdio.h>
3 #include <visp/vpRobotBiclops.h> // visp
4 
5 #include <visp_bridge/3dpose.h> // visp_bridge
6 
7 #include <geometry_msgs/Pose.h>
8 #include <geometry_msgs/PoseStamped.h>
9 #include <geometry_msgs/TwistStamped.h>
10 #include <nav_msgs/Odometry.h>
11 #include <ros/ros.h>
12 #include <tf/tf.h>
14 #include <tf/transform_datatypes.h>
15 #include <tf/transform_listener.h>
16 
17 #include <sstream>
18 
19 #ifdef VISP_HAVE_BICLOPS
20 
22 {
23 public:
25  virtual ~RosBiclopsNode();
26 
27 public:
28  int setup();
29  void setJointVel( const geometry_msgs::TwistConstPtr & );
30  void setJointPos( const geometry_msgs::PoseConstPtr & );
31  void spin();
32  void publish();
33 
34 protected:
40 
42 
43  std::string serial_port;
44 
45  vpRobotBiclops *robot;
46  geometry_msgs::PoseStamped position;
47 
48  // for odom->base_link transform
50  geometry_msgs::TransformStamped odom_trans;
51  // for resolving tf names.
52  std::string tf_prefix;
53  std::string frame_id_odom;
54  std::string frame_id_base_link;
55 
56  vpHomogeneousMatrix wMc; // world to camera transformation
57  vpColVector q; // measured joint position
58 };
59 
61 {
62  // read in config options
63  n = nh;
64 
65  ROS_INFO( "Using Biclops robot" );
66 
67  robot = NULL;
68  /*
69  * Figure out what frame_id's to use. if a tf_prefix param is specified,
70  * it will be added to the beginning of the frame_ids.
71  *
72  * e.g. rosrun ... _tf_prefix:=MyRobot (or equivalently using <param>s in
73  * roslaunch files)
74  * will result in the frame_ids being set to /MyRobot/odom etc,
75  * rather than /odom. This is useful for Multi Robot Systems.
76  * See ROS Wiki for further details.
77  */
79  // frame_id_odom = tf::resolve(tf_prefix, "odom");
80  // frame_id_base_link = tf::resolve(tf_prefix, "base_link");
81 
82  // advertise services
83  pose_pub = n.advertise< geometry_msgs::PoseStamped >( "biclops/odom", 1000 );
84 
85  // subscribe to services
86  cmd_jointvel_sub = n.subscribe( "cmd_vel", 1,
87  (boost::function< void( const geometry_msgs::TwistConstPtr & ) >)boost::bind(
88  &RosBiclopsNode::setJointVel, this, _1 ) );
89  cmd_jointpos_sub = n.subscribe( "pose", 1,
90  (boost::function< void( const geometry_msgs::PoseConstPtr & ) >)boost::bind(
91  &RosBiclopsNode::setJointPos, this, _1 ) );
92 }
93 
95 {
96  if ( robot )
97  {
98  robot->stopMotion();
99  delete robot;
100  robot = NULL;
101  }
102 }
103 
104 int
106 {
107  robot = new vpRobotBiclops( "/usr/share/BiclopsDefault.cfg" );
108  robot->setDenavitHartenbergModel( vpBiclops::DH2 );
109 
110  vpColVector qinit( 2 );
111  qinit = 0;
112  robot->setRobotState( vpRobot::STATE_POSITION_CONTROL );
113  robot->setPositioningVelocity( 40 );
114  robot->setPosition( vpRobot::ARTICULAR_FRAME, qinit );
115 
116  robot->setRobotState( vpRobot::STATE_VELOCITY_CONTROL );
117 
118  return 0;
119 }
120 
121 void
123 {
124  ros::Rate loop_rate( 15 );
125  while ( ros::ok() )
126  {
127  this->publish();
128  ros::spinOnce();
129  loop_rate.sleep();
130  }
131  // ros::spin();
132 }
133 
134 void
136 {
137  robot->getPosition( vpRobot::ARTICULAR_FRAME, q );
138 
139  position.pose.position.x = 0;
140  position.pose.position.y = 0;
141  position.pose.position.z = 0;
142  position.pose.orientation.x = q[1];
143  position.pose.orientation.y = q[0];
144  position.pose.orientation.z = 0;
145  position.pose.orientation.w = 0;
146 
147  position.header.stamp = ros::Time::now();
148 
149  // ROS_INFO( "Biclops publish pose at %f s: [%0.2f %0.2f %0.2f] - [%0.2f %0.2f %0.2f %0.2f]",
150  // position.header.stamp.toSec(),
151  // position.pose.position.x, position.pose.position.y, position.pose.position.z,
152  // position.pose.orientation.w, position.pose.orientation.x, position.pose.orientation.y,
153  // position.pose.orientation.z);
155 }
156 
157 void
158 RosBiclopsNode::setJointVel( const geometry_msgs::TwistConstPtr &msg )
159 {
161 
162  vpColVector qdot( 2 ); // Vel in rad/s for pan and tilt
163 
164  qdot[1] = msg->angular.x;
165  qdot[0] = msg->angular.y;
166 
167  ROS_INFO( "Biclops new joint vel at %f s: [%0.2f %0.2f] rad/s", veltime.toSec(), qdot[0], qdot[1] );
168  robot->setRobotState( vpRobot::STATE_VELOCITY_CONTROL );
169  robot->setVelocity( vpRobot::ARTICULAR_FRAME, qdot );
170 }
171 void
172 RosBiclopsNode::setJointPos( const geometry_msgs::PoseConstPtr &msg )
173 {
175 
176  vpColVector qdes( 2 ); // Vel in rad/s for pan and tilt
177 
178  qdes[0] = msg->orientation.x;
179  qdes[1] = msg->orientation.y;
180 
181  ROS_INFO( "Biclops new joint pos at %f s: [%0.2f %0.2f] rad/s", veltime.toSec(), qdes[0], qdes[1] );
182  robot->setRobotState( vpRobot::STATE_POSITION_CONTROL );
183  robot->setPosition( vpRobot::ARTICULAR_FRAME, qdes );
184 }
185 
186 #endif // #ifdef VISP_HAVE_BICLOPS
187 
188 int
189 main( int argc, char **argv )
190 {
191 #ifdef VISP_HAVE_BICLOPS
192  ros::init( argc, argv, "RosBiclops" );
193  ros::NodeHandle n( std::string( "~" ) );
194 
195  RosBiclopsNode *node = new RosBiclopsNode( n );
196 
197  if ( node->setup() != 0 )
198  {
199  printf( "Biclops setup failed... \n" );
200  return -1;
201  }
202 
203  node->spin();
204 
205  delete node;
206 
207  printf( "\nQuitting... \n" );
208 #else
209  printf( "This node is node available since ViSP was \nnot build with Biclops robot support...\n" );
210 #endif
211  return 0;
212 }
RosBiclopsNode::odom_broadcaster
tf::TransformBroadcaster odom_broadcaster
Definition: biclops.cpp:49
ros::Publisher
RosBiclopsNode::n
ros::NodeHandle n
Definition: biclops.cpp:35
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
RosBiclopsNode::RosBiclopsNode
RosBiclopsNode(ros::NodeHandle n)
Definition: biclops.cpp:60
ros.h
RosBiclopsNode::veltime
ros::Time veltime
Definition: biclops.cpp:41
ros::spinOnce
ROSCPP_DECL void spinOnce()
TimeBase< Time, Duration >::toSec
double toSec() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
transform_broadcaster.h
RosBiclopsNode::cmd_jointvel_sub
ros::Subscriber cmd_jointvel_sub
Definition: biclops.cpp:38
tf::TransformBroadcaster
tf::getPrefixParam
std::string getPrefixParam(ros::NodeHandle &nh)
3dpose.h
RosBiclopsNode::robot
vpRobotBiclops * robot
Definition: biclops.cpp:45
RosBiclopsNode::frame_id_odom
std::string frame_id_odom
Definition: biclops.cpp:53
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())
RosBiclopsNode::spin
void spin()
Definition: biclops.cpp:122
ros::Rate::sleep
bool sleep()
RosBiclopsNode::tf_prefix
std::string tf_prefix
Definition: biclops.cpp:52
RosBiclopsNode
Definition: biclops.cpp:21
RosBiclopsNode::vel_pub
ros::Publisher vel_pub
Definition: biclops.cpp:37
transform_listener.h
tf.h
transform_datatypes.h
RosBiclopsNode::q
vpColVector q
Definition: biclops.cpp:57
ros::Time
RosBiclopsNode::setup
int setup()
Definition: biclops.cpp:105
RosBiclopsNode::cmd_jointpos_sub
ros::Subscriber cmd_jointpos_sub
Definition: biclops.cpp:39
RosBiclopsNode::serial_port
std::string serial_port
Definition: biclops.cpp:43
RosBiclopsNode::odom_trans
geometry_msgs::TransformStamped odom_trans
Definition: biclops.cpp:50
RosBiclopsNode::frame_id_base_link
std::string frame_id_base_link
Definition: biclops.cpp:54
ros::Rate
RosBiclopsNode::wMc
vpHomogeneousMatrix wMc
Definition: biclops.cpp:56
main
int main(int argc, char **argv)
Definition: biclops.cpp:189
RosBiclopsNode::setJointPos
void setJointPos(const geometry_msgs::PoseConstPtr &)
Definition: biclops.cpp:172
ROS_INFO
#define ROS_INFO(...)
RosBiclopsNode::publish
void publish()
Definition: biclops.cpp:135
RosBiclopsNode::setJointVel
void setJointVel(const geometry_msgs::TwistConstPtr &)
Definition: biclops.cpp:158
RosBiclopsNode::pose_pub
ros::Publisher pose_pub
Definition: biclops.cpp:36
RosBiclopsNode::position
geometry_msgs::PoseStamped position
Definition: biclops.cpp:46
RosBiclopsNode::~RosBiclopsNode
virtual ~RosBiclopsNode()
Definition: biclops.cpp:94
ros::NodeHandle
ros::Subscriber
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