3 #include <visp/vpRobotBiclops.h>
7 #include <geometry_msgs/Pose.h>
8 #include <geometry_msgs/PoseStamped.h>
9 #include <geometry_msgs/TwistStamped.h>
10 #include <nav_msgs/Odometry.h>
19 #ifdef VISP_HAVE_BICLOPS
29 void setJointVel(
const geometry_msgs::TwistConstPtr & );
30 void setJointPos(
const geometry_msgs::PoseConstPtr & );
56 vpHomogeneousMatrix
wMc;
87 (boost::function<
void(
const geometry_msgs::TwistConstPtr & ) >)boost::bind(
90 (boost::function<
void(
const geometry_msgs::PoseConstPtr & ) >)boost::bind(
107 robot =
new vpRobotBiclops(
"/usr/share/BiclopsDefault.cfg" );
108 robot->setDenavitHartenbergModel( vpBiclops::DH2 );
110 vpColVector qinit( 2 );
112 robot->setRobotState( vpRobot::STATE_POSITION_CONTROL );
113 robot->setPositioningVelocity( 40 );
114 robot->setPosition( vpRobot::ARTICULAR_FRAME, qinit );
116 robot->setRobotState( vpRobot::STATE_VELOCITY_CONTROL );
137 robot->getPosition( vpRobot::ARTICULAR_FRAME,
q );
162 vpColVector qdot( 2 );
164 qdot[1] = msg->angular.x;
165 qdot[0] = msg->angular.y;
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 );
176 vpColVector qdes( 2 );
178 qdes[0] = msg->orientation.x;
179 qdes[1] = msg->orientation.y;
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 );
186 #endif // #ifdef VISP_HAVE_BICLOPS
191 #ifdef VISP_HAVE_BICLOPS
197 if ( node->
setup() != 0 )
199 printf(
"Biclops setup failed... \n" );
207 printf(
"\nQuitting... \n" );
209 printf(
"This node is node available since ViSP was \nnot build with Biclops robot support...\n" );