6 #include <std_msgs/Float64MultiArray.h> 7 #include <sensor_msgs/JointState.h> 8 #include <geometry_msgs/TwistStamped.h> 9 #include <geometry_msgs/Pose.h> 10 #include <geometry_msgs/PoseStamped.h> 11 #include <nav_msgs/Odometry.h> 17 #include <visp3/core/vpMath.h> 18 #include <visp3/core/vpIoTools.h> 19 #include <visp3/core/vpHomogeneousMatrix.h> 20 #include <visp3/robot/vpRobotViper850.h> 25 #ifdef VISP_HAVE_VIPER850 31 virtual ~RosViper850Node();
35 void setCameraVel(
const geometry_msgs::TwistStampedConstPtr &);
36 void setJointVel(
const sensor_msgs::JointStateConstPtr &);
37 void setRefVel(
const geometry_msgs::TwistStampedConstPtr &);
50 std::string setControlMode;
51 std::string getStateSpace;
52 std::string cmdVelTopicName;
53 std::string endEffectorType;
54 std::string customToolTransformationFileName;
58 std::string serial_port;
60 vpRobotViper850 *robot;
61 geometry_msgs::PoseStamped position;
62 sensor_msgs::JointState jointState;
63 std_msgs::Float64MultiArray jacobian;
67 geometry_msgs::TransformStamped odom_trans;
69 std::string tf_prefix;
70 std::string frame_id_odom;
71 std::string frame_id_base_link;
73 vpHomogeneousMatrix wMc;
83 ROS_INFO(
"Launch Viper850 robot ros node");
86 n.param<std::string>(
"set_control_mode", setControlMode,
"tool_frame");
87 n.param<std::string>(
"get_state_space", getStateSpace,
"tool_frame");
88 n.param<std::string>(
"cmd_vel_topic_name", cmdVelTopicName,
"cmd_vel");
89 n.param<std::string>(
"end_effector", endEffectorType,
"TOOL_PTGREY_FLEA2_CAMERA");
90 n.param<std::string>(
"custom_tool_transformation_filename", customToolTransformationFileName,
"");
113 if (setControlMode ==
"joint_space") {
114 ROS_INFO(
"Viper850 robot controlled in joint space");
115 jointState_pub = n.advertise<sensor_msgs::JointState>(
"joint_state", 10);
116 jacobian_pub = n.advertise<std_msgs::Float64MultiArray>(
"jacobian", 10);
117 cmd_jointvel_sub = n.subscribe( cmdVelTopicName, 1, (boost::function <
void(
const sensor_msgs::JointStateConstPtr&)>) boost::bind( &RosViper850Node::setJointVel,
this, _1 ));
119 else if (setControlMode ==
"camera_frame") {
120 ROS_INFO(
"Viper850 robot controlled in camera frame");
121 pose_pub = n.advertise<geometry_msgs::PoseStamped>(
"pose", 10);
122 vel_pub = n.advertise<geometry_msgs::TwistStamped>(
"velocity", 10);
123 cmd_camvel_sub = n.subscribe( cmdVelTopicName, 1, (boost::function <
void(
const geometry_msgs::TwistStampedConstPtr&)>) boost::bind( &RosViper850Node::setCameraVel,
this, _1 ));
125 else if (setControlMode ==
"reference_frame") {
126 ROS_INFO(
"Viper850 robot controlled in reference frame");
127 pose_pub = n.advertise<geometry_msgs::PoseStamped>(
"pose", 10);
128 vel_pub = n.advertise<geometry_msgs::TwistStamped>(
"velocity", 10);
129 cmd_refvel_sub = n.subscribe( cmdVelTopicName, 1, (boost::function <
void(
const geometry_msgs::TwistStampedConstPtr&)>) boost::bind( &RosViper850Node::setRefVel,
this, _1 ));
133 RosViper850Node::~RosViper850Node()
142 int RosViper850Node::setup()
144 robot =
new vpRobotViper850;
146 if (endEffectorType ==
"TOOL_PTGREY_FLEA2_CAMERA") {
147 robot->init(vpViper850::TOOL_PTGREY_FLEA2_CAMERA, vpCameraParameters::perspectiveProjWithDistortion);
149 else if (endEffectorType ==
"TOOL_GENERIC_CAMERA") {
150 robot->init(vpViper850::TOOL_GENERIC_CAMERA, vpCameraParameters::perspectiveProjWithDistortion);
152 else if (endEffectorType ==
"TOOL_CUSTOM") {
153 if (vpIoTools::checkFilename(customToolTransformationFileName) ==
false) {
154 ROS_ERROR(
"Viper850: Missing or bad filename for eMt custom tool transformation");
158 vpHomogeneousMatrix eMt;
159 std::ifstream
f(customToolTransformationFileName.c_str());
164 catch(vpException &e) {
165 ROS_ERROR_STREAM(
"Viper850: Cannot load eMt custom tool transformation from \"" << customToolTransformationFileName <<
"\": " << e.getStringMessage());
170 robot->init(vpViper850::TOOL_CUSTOM, eMt);
173 robot->setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
178 void RosViper850Node::spin()
188 void RosViper850Node::publish()
191 robot->getPosition(vpRobot::ARTICULAR_FRAME, q, timestamp);
193 if (getStateSpace ==
"joint_space") {
195 robot->getVelocity(vpRobot::ARTICULAR_FRAME, qdot, timestamp);
196 jointState.position.clear();
197 jointState.velocity.clear();
198 jointState.header.stamp =
ros::Time(timestamp);
199 for (
unsigned int i=0; i<qdot.size(); i++) {
200 jointState.position.push_back(q[i]);
201 jointState.velocity.push_back(qdot[i]);
203 jointState_pub.publish(jointState);
207 vpHomogeneousMatrix eMc;
209 vpMatrix cJc = vpVelocityTwistMatrix(eMc.inverse()) * eJe;
211 jacobian.data.clear();
212 jacobian.layout.dim.resize(2);
214 jacobian.layout.dim[0].label =
"height";
215 jacobian.layout.dim[0].size = cJc.getRows();
216 jacobian.layout.dim[0].stride = cJc.size();
217 jacobian.layout.dim[1].label =
"width";
218 jacobian.layout.dim[1].size = cJc.getCols();
219 jacobian.layout.dim[1].stride = cJc.getCols();
220 for(
unsigned int i =0; i< cJc.size(); i++)
221 jacobian.data.push_back( cJc.data[i]);
222 jacobian_pub.publish(jacobian);
224 else if (getStateSpace ==
"camera_frame") {
225 wMc = robot->get_fMc(q);
227 position.header.stamp =
ros::Time(timestamp);
233 pose_pub.publish(position);
236 robot->getVelocity(vpRobot::CAMERA_FRAME, vel, timestamp);
237 geometry_msgs::TwistStamped vel_msg;
238 vel_msg.header.stamp =
ros::Time(timestamp);
239 vel_msg.twist.linear.x = vel[0];
240 vel_msg.twist.linear.y = vel[1];
241 vel_msg.twist.linear.z = vel[2];
242 vel_msg.twist.angular.x = vel[3];
243 vel_msg.twist.angular.y = vel[4];
244 vel_msg.twist.angular.z = vel[5];
245 vel_pub.publish(vel_msg);
247 else if (getStateSpace ==
"reference_frame") {
248 wMc = robot->get_fMc(q);
250 position.header.stamp =
ros::Time(timestamp);
256 pose_pub.publish(position);
259 robot->getVelocity(vpRobot::REFERENCE_FRAME, vel, timestamp);
260 geometry_msgs::TwistStamped vel_msg;
261 vel_msg.header.stamp =
ros::Time(timestamp);
262 vel_msg.twist.linear.x = vel[0];
263 vel_msg.twist.linear.y = vel[1];
264 vel_msg.twist.linear.z = vel[2];
265 vel_msg.twist.angular.x = vel[3];
266 vel_msg.twist.angular.y = vel[4];
267 vel_msg.twist.angular.z = vel[5];
268 vel_pub.publish(vel_msg);
273 RosViper850Node::setCameraVel(
const geometry_msgs::TwistStampedConstPtr &msg)
279 vc[0] = msg->twist.linear.x;
280 vc[1] = msg->twist.linear.y;
281 vc[2] = msg->twist.linear.z;
283 vc[3] = msg->twist.angular.x;
284 vc[4] = msg->twist.angular.y;
285 vc[5] = msg->twist.angular.z;
287 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",
289 vc[0], vc[1], vc[2], vc[3], vc[4], vc[5]);
290 robot->setVelocity(vpRobot::CAMERA_FRAME, vc);
294 RosViper850Node::setJointVel(
const sensor_msgs::JointStateConstPtr &msg)
298 if (msg->velocity.size() != 6) {
299 ROS_ERROR(
"Viper850: Cannot apply a joint velocity vector that is not 6 dimensional");
304 for(
unsigned int i=0; i<msg->velocity.size(); i++)
305 qdot[i] = msg->velocity[i];
307 ROS_INFO(
"Viper850 new joint vel at %f s: [%0.2f %0.2f %0.2f %0.2f %0.2f %0.2f] rad/s",
309 qdot[0], qdot[1], qdot[2], qdot[3], qdot[4], qdot[5]);
311 robot->setVelocity(vpRobot::ARTICULAR_FRAME, qdot);
315 RosViper850Node::setRefVel(
const geometry_msgs::TwistStampedConstPtr &msg)
321 vref[0] = msg->twist.linear.x;
322 vref[1] = msg->twist.linear.y;
323 vref[2] = msg->twist.linear.z;
325 vref[3] = msg->twist.angular.x;
326 vref[4] = msg->twist.angular.y;
327 vref[5] = msg->twist.angular.z;
329 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",
331 vref[0], vref[1], vref[2], vref[3], vref[4], vref[5]);
332 robot->setVelocity(vpRobot::REFERENCE_FRAME, vref);
335 #endif // #ifdef VISP_HAVE_Viper850 337 int main(
int argc,
char** argv )
339 #ifdef VISP_HAVE_VIPER850 343 RosViper850Node *node =
new RosViper850Node(n);
345 if( node->setup() != 0 )
347 printf(
"Viper850 setup failed... \n" );
355 printf(
"\nQuitting... \n" );
357 printf(
"The Viper850 robot is not supported by ViSP...\n");
std::string getPrefixParam(ros::NodeHandle &nh)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
geometry_msgs::Pose toGeometryMsgsPose(const vpHomogeneousMatrix &mat)
int main(int argc, char **argv)
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()