jaco_arm.h
Go to the documentation of this file.
00001 /*
00002  * jaco_arm_driver.h
00003  *
00004  *  Created on: Feb 26, 2013
00005  *  Modified on: June 25, 2013
00006  *      Author: mdedonato, Clearpath Robotics
00007  *
00008  */
00009 
00010 #ifndef JACO_ARM_DRIVER_H_
00011 #define JACO_ARM_DRIVER_H_
00012 
00013 #include <ros/ros.h>
00014 #include <jaco_driver/jaco_api.h>
00015 #include "jaco_driver/KinovaTypes.h"
00016 #include <geometry_msgs/PoseStamped.h>
00017 #include <geometry_msgs/TwistStamped.h>
00018 #include <tf/tf.h>
00019 #include <tf/transform_listener.h>
00020 #include "jaco_driver/JointVelocity.h"
00021 #include "jaco_driver/FingerPosition.h"
00022 #include "jaco_driver/JointAngles.h"
00023 #include "sensor_msgs/JointState.h"
00024 
00025 #include <jaco_driver/Stop.h>
00026 #include <jaco_driver/Start.h>
00027 #include <jaco_driver/HomeArm.h>
00028 
00029 #include "jaco_driver/jaco_comm.h"
00030 
00031 #include <time.h>
00032 #include <math.h>
00033 #include <vector>
00034 
00035 namespace jaco
00036 {
00037 
00038 class JacoArm
00039 {
00040         public:
00041         JacoArm(JacoComm &, ros::NodeHandle &);
00042         ~JacoArm();
00043         void GoHome(void);
00044         void CalculatePostion(void);
00045         void PositionTimer(const ros::TimerEvent&);
00046         void CartesianVelTimer(const ros::TimerEvent&);
00047         void JointVelTimer(const ros::TimerEvent&);
00048         void StatusTimer(const ros::TimerEvent&);
00049         void VelocityMSG(const jaco_driver::JointVelocityConstPtr&);
00050 
00051         void CartesianVelocityMSG(const geometry_msgs::TwistStampedConstPtr&);
00052         void BroadCastAngles(void);
00053         void BroadCastPosition(void);
00054         void BroadCastFingerPosition(void);
00055 
00056         bool StopSRV(jaco_driver::Stop::Request &req, jaco_driver::Stop::Response &res);
00057         bool StartSRV(jaco_driver::Start::Request &req, jaco_driver::Start::Response &res);
00058         bool HomeArmSRV(jaco_driver::HomeArm::Request &req, jaco_driver::HomeArm::Response &res);
00059 
00060 
00061         private:
00062         JacoComm &arm;
00063 
00064         /* Subscribers */
00065         ros::Subscriber JointVelocity_sub;
00066         ros::Subscriber CartesianVelocity_sub;
00067         ros::Subscriber SoftwarePause_sub;
00068 
00069         /* Publishers */
00070         ros::Publisher JointAngles_pub;
00071         ros::Publisher ToolPosition_pub;
00072         ros::Publisher FingerPosition_pub;
00073         ros::Publisher JointState_pub;
00074 
00075         /* Services */
00076         ros::ServiceServer stop_service;
00077         ros::ServiceServer start_service;
00078         ros::ServiceServer homing_service;
00079 
00080         ros::Timer status_timer;
00081         ros::Timer cartesian_vel_timer;
00082         ros::Timer joint_vel_timer;
00083         bool cartesian_vel_timer_flag;
00084         bool joint_vel_timer_flag;
00085 
00086         AngularInfo joint_velocities;
00087         CartesianInfo cartesian_velocities;
00088 
00089         ros::Time last_joint_update;
00090         ros::Time last_cartesian_update;
00091 
00092         tf::TransformListener listener;
00093 
00094         ros::Time last_update_time;
00095         ros::Duration update_time;
00096         uint8_t previous_state;
00097 };
00098 
00099 }
00100 
00101 #endif /* JACO_ARM_DRIVER_H_ */


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