Go to the documentation of this file.00001 #include <stdio.h>
00002 #include <math.h>
00003 #include <visp/vpRobotBiclops.h>
00004
00005 #include <visp_bridge/3dpose.h>
00006
00007 #include <ros/ros.h>
00008 #include <geometry_msgs/TwistStamped.h>
00009 #include <geometry_msgs/Pose.h>
00010 #include <geometry_msgs/PoseStamped.h>
00011 #include <nav_msgs/Odometry.h>
00012 #include <tf/tf.h>
00013 #include <tf/transform_listener.h>
00014 #include <tf/transform_broadcaster.h>
00015 #include <tf/transform_datatypes.h>
00016
00017
00018 #include <sstream>
00019
00020 #ifdef VISP_HAVE_BICLOPS
00021
00022 class RosBiclopsNode
00023 {
00024 public:
00025 RosBiclopsNode(ros::NodeHandle n);
00026 virtual ~RosBiclopsNode();
00027
00028 public:
00029 int setup();
00030 void setJointVel( const geometry_msgs::TwistConstPtr &);
00031 void setJointPos( const geometry_msgs::PoseConstPtr &);
00032 void spin();
00033 void publish();
00034
00035 protected:
00036 ros::NodeHandle n;
00037 ros::Publisher pose_pub;
00038 ros::Publisher vel_pub;
00039 ros::Subscriber cmd_jointvel_sub;
00040 ros::Subscriber cmd_jointpos_sub;
00041
00042 ros::Time veltime;
00043
00044 std::string serial_port;
00045
00046 vpRobotBiclops *robot;
00047 geometry_msgs::PoseStamped position;
00048
00049
00050 tf::TransformBroadcaster odom_broadcaster;
00051 geometry_msgs::TransformStamped odom_trans;
00052
00053 std::string tf_prefix;
00054 std::string frame_id_odom;
00055 std::string frame_id_base_link;
00056
00057 vpHomogeneousMatrix wMc;
00058 vpColVector q;
00059
00060 };
00061
00062
00063 RosBiclopsNode::RosBiclopsNode(ros::NodeHandle nh)
00064 {
00065
00066 n = nh;
00067
00068 ROS_INFO( "Using Biclops robot" );
00069
00070 robot = NULL;
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081 tf_prefix = tf::getPrefixParam(n);
00082
00083
00084
00085
00086 pose_pub = n.advertise<geometry_msgs::PoseStamped>("biclops/odom", 1000);
00087
00088
00089 cmd_jointvel_sub = n.subscribe( "cmd_vel", 1, (boost::function < void(const geometry_msgs::TwistConstPtr&)>) boost::bind( &RosBiclopsNode::setJointVel, this, _1 ));
00090 cmd_jointpos_sub = n.subscribe( "pose", 1, (boost::function < void(const geometry_msgs::PoseConstPtr&)>) boost::bind( &RosBiclopsNode::setJointPos, this, _1 ));
00091 }
00092
00093 RosBiclopsNode::~RosBiclopsNode()
00094 {
00095 if (robot) {
00096 robot->stopMotion();
00097 delete robot;
00098 robot = NULL;
00099 }
00100 }
00101
00102 int RosBiclopsNode::setup()
00103 {
00104 robot = new vpRobotBiclops("/usr/share/BiclopsDefault.cfg");
00105 robot->setDenavitHartenbergModel(vpBiclops::DH2);
00106
00107 vpColVector qinit(2);
00108 qinit = 0;
00109 robot->setRobotState(vpRobot::STATE_POSITION_CONTROL) ;
00110 robot->setPositioningVelocity(40);
00111 robot->setPosition(vpRobot::ARTICULAR_FRAME, qinit);
00112
00113 robot->setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
00114
00115 return 0;
00116 }
00117
00118 void RosBiclopsNode::spin()
00119 {
00120 ros::Rate loop_rate(15);
00121 while(ros::ok()){
00122 this->publish();
00123 ros::spinOnce();
00124 loop_rate.sleep();
00125 }
00126
00127 }
00128
00129 void RosBiclopsNode::publish()
00130 {
00131 robot->getPosition(vpRobot::ARTICULAR_FRAME, q);
00132
00133 position.pose.position.x = 0;
00134 position.pose.position.y = 0;
00135 position.pose.position.z = 0;
00136 position.pose.orientation.x = q[1];
00137 position.pose.orientation.y = q[0];
00138 position.pose.orientation.z = 0;
00139 position.pose.orientation.w = 0;
00140
00141 position.header.stamp = ros::Time::now();
00142
00143
00144
00145
00146
00147 pose_pub.publish(position);
00148 }
00149
00150 void
00151 RosBiclopsNode::setJointVel( const geometry_msgs::TwistConstPtr &msg)
00152 {
00153 veltime = ros::Time::now();
00154
00155 vpColVector qdot(2);
00156
00157 qdot[1] = msg->angular.x;
00158 qdot[0] = msg->angular.y;
00159
00160
00161 ROS_INFO( "Biclops new joint vel at %f s: [%0.2f %0.2f] rad/s",
00162 veltime.toSec(),
00163 qdot[0], qdot[1]);
00164 robot->setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
00165 robot->setVelocity(vpRobot::ARTICULAR_FRAME, qdot);
00166 }
00167 void
00168 RosBiclopsNode::setJointPos( const geometry_msgs::PoseConstPtr &msg)
00169 {
00170 veltime = ros::Time::now();
00171
00172 vpColVector qdes(2);
00173
00174 qdes[0] = msg->orientation.x;
00175 qdes[1] = msg->orientation.y;
00176
00177 ROS_INFO( "Biclops new joint pos at %f s: [%0.2f %0.2f] rad/s",
00178 veltime.toSec(),
00179 qdes[0], qdes[1]);
00180 robot->setRobotState(vpRobot::STATE_POSITION_CONTROL);
00181 robot->setPosition(vpRobot::ARTICULAR_FRAME, qdes);
00182 }
00183
00184 #endif // #ifdef VISP_HAVE_BICLOPS
00185
00186
00187 int main( int argc, char** argv )
00188 {
00189 #ifdef VISP_HAVE_BICLOPS
00190 ros::init(argc,argv, "RosBiclops");
00191 ros::NodeHandle n(std::string("~"));
00192
00193 RosBiclopsNode *node = new RosBiclopsNode(n);
00194
00195 if( node->setup() != 0 )
00196 {
00197 printf( "Biclops setup failed... \n" );
00198 return -1;
00199 }
00200
00201 node->spin();
00202
00203 delete node;
00204
00205 printf( "\nQuitting... \n" );
00206 #else
00207 printf("This node is node available since ViSP was \nnot build with Biclops robot support...\n");
00208 #endif
00209 return 0;
00210 }