test_jaco_arm_car_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 <jaco_driver/test_jaco_arm_car_vel.h>
00019 
00020 using namespace std;
00021 
00022 
00023 CartesianVelTest::CartesianVelTest(ros::NodeHandle nh,std::string JointVelocity)
00024 {
00025          pub = nh.advertise<geometry_msgs::TwistStamped>(JointVelocity,
00026                                 2);
00027           x_vel = 0;
00028           y_vel = 0;
00029           z_vel = 0;
00030           rx_vel = 0;
00031           ry_vel = 0;
00032           rz_vel = 0;
00033 
00034                 dr_call = boost::bind(&CartesianVelTest::callback,this, _1, _2);
00035                   dr_server.setCallback(dr_call);
00036                 timer = nh.createTimer(ros::Duration(0.1),&CartesianVelTest::TimerCallback,this);
00037                 //ROS_INFO("Start");
00038 
00039 }
00040 void CartesianVelTest::TimerCallback(const ros::TimerEvent&)
00041 {
00042         geometry_msgs::TwistStamped test_msg;
00043 
00044 
00045         test_msg.header.frame_id        = "/jaco_arm_api";
00046         test_msg.header.stamp   = ros::Time().now();
00047 
00048 
00049 
00050                         test_msg.twist.linear.x = x_vel;
00051                         test_msg.twist.linear.y = y_vel;
00052                         test_msg.twist.linear.z = z_vel;
00053                         test_msg.twist.angular.x= rx_vel;
00054                         test_msg.twist.angular.y = ry_vel;
00055                         test_msg.twist.angular.z = rz_vel;
00056 
00057 
00058                         pub.publish(test_msg);
00059                 //      ROS_INFO("Timer");
00060 
00061 
00062 }
00063 
00064 void CartesianVelTest::callback(jaco_driver::JacoVelocityConfig &config, uint32_t level) {
00065 
00066          x_vel=config.X_Vel;
00067          y_vel=config.Y_Vel;
00068          z_vel=config.Z_Vel;
00069          rx_vel=config.RX_Vel;
00070          ry_vel=config.RY_Vel;
00071          rz_vel=config.RZ_Vel;
00072 
00073         //      ROS_INFO("Reconfigure");
00074 
00075 
00076 }
00077 
00078 int main(int argc, char **argv) {
00079 
00080         /* Set up ROS */
00081         ros::init(argc, argv, "test_jaco_arm_car_vel");
00082         ros::NodeHandle nh;
00083         ros::NodeHandle param_nh("~");
00084 
00085         std::string JointVelocity("CartesianVelocity"); 
00086 
00087         CartesianVelTest test_node(nh,JointVelocity);
00088 
00089 
00090         ros::spin();
00091 }
00092 


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