follow_joint_trajectory_client.h
Go to the documentation of this file.
00001 /*
00002  * follow_joint_trajectory_client.h
00003  *
00004  *  Created on: 06.11.2011
00005  *      Author: martin
00006  */
00007 
00008 #ifndef FOLLOW_JOINT_TRAJECTORY_CLIENT_H_
00009 #define FOLLOW_JOINT_TRAJECTORY_CLIENT_H_
00010 
00011 #include <ros/ros.h>
00012 #include <control_msgs/FollowJointTrajectoryAction.h>
00013 #include <actionlib/client/simple_action_client.h>
00014 #include <sensor_msgs/JointState.h>
00015 #include <arm_navigation_msgs/FilterJointTrajectory.h>
00016 #include <trajectory_msgs/JointTrajectory.h>
00017 
00018 namespace katana_tutorials
00019 {
00020 
00021 typedef actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> TrajClient;
00022 
00023 class FollowJointTrajectoryClient
00024 {
00025 public:
00026   FollowJointTrajectoryClient();
00027   virtual ~FollowJointTrajectoryClient();
00028 
00029   void startTrajectory(control_msgs::FollowJointTrajectoryGoal goal);
00030   control_msgs::FollowJointTrajectoryGoal makeArmUpTrajectory();
00031   actionlib::SimpleClientGoalState getState();
00032 
00033 private:
00034   ros::NodeHandle nh_;
00035   TrajClient traj_client_;
00036   ros::Subscriber joint_state_sub_;
00037   std::vector<std::string> joint_names_;
00038   bool got_joint_state_;
00039   std::vector<double> current_joint_state_;
00040   ros::AsyncSpinner spinner_;
00041 
00042   void jointStateCB(const sensor_msgs::JointState::ConstPtr &msg);
00043   trajectory_msgs::JointTrajectory filterJointTrajectory(const trajectory_msgs::JointTrajectory &input);
00044 };
00045 
00046 } /* namespace katana_tutorials */
00047 #endif /* FOLLOW_JOINT_TRAJECTORY_CLIENT_H_ */


katana_tutorials
Author(s): Martin Günther
autogenerated on Mon Oct 6 2014 10:45:24