test_jaco_arm_vel.cpp
Go to the documentation of this file.
00001 //============================================================================
00002 // Name        : Jaco.cpp
00003 // Author      : 
00004 // Version     :
00005 // Copyright   : Your copyright notice
00006 // Description : Hello World in C++, Ansi-style
00007 //============================================================================
00008 
00017 //License File
00018 #include <geometry_msgs/PoseStamped.h>
00019 #include <geometry_msgs/TwistStamped.h>
00020 #include <tf/tf.h>
00021 #include <ros/ros.h>
00022 #include <jaco_driver/cartesian_velocity.h>
00023 
00024 using namespace std;
00025 ros::Publisher pub;
00026 void TimerCallback(const ros::TimerEvent&)
00027 {
00028         jaco_driver::cartesian_velocity test_msg;
00029 
00030                         test_msg.Velocity_X = 0.0;
00031                         test_msg.Velocity_Y = 10;
00032                         test_msg.Velocity_Z = 0;
00033                         test_msg.Velocity_TX = 0;
00034                         test_msg.Velocity_TY = 0;
00035                         test_msg.Velocity_TZ = 0;
00036 
00037 
00038                         pub.publish(test_msg);
00039 
00040 
00041 }
00042 
00043 int main(int argc, char **argv) {
00044 
00045         /* Set up ROS */
00046         ros::init(argc, argv, "test_jaco_arm_vel");
00047         ros::NodeHandle nh;
00048         ros::NodeHandle param_nh("~");
00049 
00050         std::string JointVelocity("CartesianVelocity"); 
00051 
00052          pub = nh.advertise<jaco_driver::cartesian_velocity>(JointVelocity,
00053                         2);
00054 
00055         ros::Timer timer = nh.createTimer(ros::Duration(0.01),TimerCallback);
00056 
00057 
00058         ros::spin();
00059 }
00060 


jaco_driver
Author(s): Jeff Schmidt (Clearpath), Alex Bencz (Clearpath), Matt DeDonato (WPI)
autogenerated on Mon Jan 6 2014 11:23:43