5 #include <geometry_msgs/Pose.h>     6 #include <geometry_msgs/PoseStamped.h>     7 #include <geometry_msgs/TwistStamped.h>     8 #include <nav_msgs/Odometry.h>    10 #include <sensor_msgs/JointState.h>    11 #include <std_msgs/Float64MultiArray.h>    17 #include <visp3/core/vpHomogeneousMatrix.h>    18 #include <visp3/core/vpIoTools.h>    19 #include <visp3/core/vpMath.h>    20 #include <visp3/robot/vpRobotViper850.h>    24 #ifdef VISP_HAVE_VIPER850    34   void setCameraVel( 
const geometry_msgs::TwistStampedConstPtr & );
    35   void setJointVel( 
const sensor_msgs::JointStateConstPtr & );
    36   void setRefVel( 
const geometry_msgs::TwistStampedConstPtr & );
    72   vpHomogeneousMatrix 
wMc; 
    81   ROS_INFO( 
"Launch Viper850 robot ros node" );
   110   if ( setControlMode == 
"joint_space" )
   112     ROS_INFO( 
"Viper850 robot controlled in joint space" );
   116                                     (boost::function< 
void( 
const sensor_msgs::JointStateConstPtr & ) >)boost::bind(
   119   else if ( setControlMode == 
"camera_frame" )
   121     ROS_INFO( 
"Viper850 robot controlled in camera frame" );
   125                                   (boost::function< 
void( 
const geometry_msgs::TwistStampedConstPtr & ) >)boost::bind(
   128   else if ( setControlMode == 
"reference_frame" )
   130     ROS_INFO( 
"Viper850 robot controlled in reference frame" );
   134                                   (boost::function< 
void( 
const geometry_msgs::TwistStampedConstPtr & ) >)boost::bind(
   152   robot = 
new vpRobotViper850;
   156     robot->init( vpViper850::TOOL_PTGREY_FLEA2_CAMERA, vpCameraParameters::perspectiveProjWithDistortion );
   160     robot->init( vpViper850::TOOL_GENERIC_CAMERA, vpCameraParameters::perspectiveProjWithDistortion );
   166       ROS_ERROR( 
"Viper850: Missing or bad filename for eMt custom tool transformation" );
   170     vpHomogeneousMatrix eMt;
   177     catch ( vpException &e )
   179       ROS_ERROR_STREAM( 
"Viper850: Cannot load eMt custom tool transformation from \""   185     robot->init( vpViper850::TOOL_CUSTOM, eMt );
   188   robot->setRobotState( vpRobot::STATE_VELOCITY_CONTROL );
   209   robot->getPosition( vpRobot::ARTICULAR_FRAME, 
q, timestamp );
   214     robot->getVelocity( vpRobot::ARTICULAR_FRAME, qdot, timestamp );
   218     for ( 
unsigned int i = 0; i < qdot.size(); i++ )
   226     robot->get_eJe( eJe );
   227     vpHomogeneousMatrix eMc;
   228     robot->get_eMc( eMc );
   229     vpMatrix cJc = vpVelocityTwistMatrix( eMc.inverse() ) * eJe;
   234     jacobian.layout.dim[0].label  = 
"height";
   235     jacobian.layout.dim[0].size   = cJc.getRows();
   236     jacobian.layout.dim[0].stride = cJc.size();
   237     jacobian.layout.dim[1].label  = 
"width";
   238     jacobian.layout.dim[1].size   = cJc.getCols();
   239     jacobian.layout.dim[1].stride = cJc.getCols();
   240     for ( 
unsigned int i = 0; i < cJc.size(); i++ )
   241       jacobian.data.push_back( cJc.data[i] );
   257     vpColVector vel( 6 );
   258     robot->getVelocity( vpRobot::CAMERA_FRAME, vel, timestamp );
   259     geometry_msgs::TwistStamped vel_msg;
   260     vel_msg.header.stamp    = 
ros::Time( timestamp );
   261     vel_msg.twist.linear.x  = vel[0];
   262     vel_msg.twist.linear.y  = vel[1];
   263     vel_msg.twist.linear.z  = vel[2];
   264     vel_msg.twist.angular.x = vel[3];
   265     vel_msg.twist.angular.y = vel[4];
   266     vel_msg.twist.angular.z = vel[5];
   282     vpColVector vel( 6 );
   283     robot->getVelocity( vpRobot::REFERENCE_FRAME, vel, timestamp );
   284     geometry_msgs::TwistStamped vel_msg;
   285     vel_msg.header.stamp    = 
ros::Time( timestamp );
   286     vel_msg.twist.linear.x  = vel[0];
   287     vel_msg.twist.linear.y  = vel[1];
   288     vel_msg.twist.linear.z  = vel[2];
   289     vel_msg.twist.angular.x = vel[3];
   290     vel_msg.twist.angular.y = vel[4];
   291     vel_msg.twist.angular.z = vel[5];
   303   vc[0] = msg->twist.linear.x;
   304   vc[1] = msg->twist.linear.y;
   305   vc[2] = msg->twist.linear.z;
   307   vc[3] = msg->twist.angular.x;
   308   vc[4] = msg->twist.angular.y;
   309   vc[5] = msg->twist.angular.z;
   311   ROS_INFO( 
"Viper850 new camera vel at %f s: [%0.2f %0.2f %0.2f] m/s [%0.2f %0.2f %0.2f] rad/s", 
veltime.
toSec(),
   312             vc[0], vc[1], vc[2], vc[3], vc[4], vc[5] );
   313   robot->setVelocity( vpRobot::CAMERA_FRAME, vc );
   321   if ( msg->velocity.size() != 6 )
   323     ROS_ERROR( 
"Viper850: Cannot apply a joint velocity vector that is not 6 dimensional" );
   326   vpColVector qdot( 6 ); 
   328   for ( 
unsigned int i = 0; i < msg->velocity.size(); i++ )
   329     qdot[i] = msg->velocity[i];
   331   ROS_INFO( 
"Viper850 new joint vel at %f s: [%0.2f %0.2f %0.2f %0.2f %0.2f %0.2f] rad/s", 
veltime.
toSec(), qdot[0],
   332             qdot[1], qdot[2], qdot[3], qdot[4], qdot[5] );
   334   robot->setVelocity( vpRobot::ARTICULAR_FRAME, qdot );
   342   vpColVector vref( 6 ); 
   344   vref[0] = msg->twist.linear.x;
   345   vref[1] = msg->twist.linear.y;
   346   vref[2] = msg->twist.linear.z;
   348   vref[3] = msg->twist.angular.x;
   349   vref[4] = msg->twist.angular.y;
   350   vref[5] = msg->twist.angular.z;
   352   ROS_INFO( 
"Viper850 new reference vel at %f s: [%0.2f %0.2f %0.2f] m/s [%0.2f %0.2f %0.2f] rad/s", 
veltime.
toSec(),
   353             vref[0], vref[1], vref[2], vref[3], vref[4], vref[5] );
   354   robot->setVelocity( vpRobot::REFERENCE_FRAME, vref );
   357 #endif // #ifdef VISP_HAVE_Viper850   362 #ifdef VISP_HAVE_VIPER850   368   if ( node->
setup() != 0 )
   370     printf( 
"Viper850 setup failed... \n" );
   378   printf( 
"\nQuitting... \n" );
   380   printf( 
"The Viper850 robot is not supported by ViSP...\n" );
 ros::Publisher jointState_pub
ros::Subscriber cmd_refvel_sub
std::string getPrefixParam(ros::NodeHandle &nh)
void setCameraVel(const geometry_msgs::TwistStampedConstPtr &)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual ~RosViper850Node()
tf::TransformBroadcaster odom_broadcaster
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setRefVel(const geometry_msgs::TwistStampedConstPtr &)
RosViper850Node(ros::NodeHandle n)
std_msgs::Float64MultiArray jacobian
std::string frame_id_base_link
geometry_msgs::Pose toGeometryMsgsPose(const vpHomogeneousMatrix &mat)
geometry_msgs::PoseStamped position
std::string customToolTransformationFileName
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber cmd_camvel_sub
int main(int argc, char **argv)
std::string getStateSpace
void setJointVel(const sensor_msgs::JointStateConstPtr &)
ros::Subscriber cmd_jointvel_sub
std::string setControlMode
geometry_msgs::TransformStamped odom_trans
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string endEffectorType
sensor_msgs::JointState jointState
std::string frame_id_odom
#define ROS_ERROR_STREAM(args)
ros::Publisher jacobian_pub
ROSCPP_DECL void spinOnce()
std::string cmdVelTopicName