pr2_joint_trajectory_client.h
Go to the documentation of this file.
1 /*
2  * follow_joint_trajectory_client.h
3  *
4  * Created on: 06.11.2011
5  * Author: martin
6  */
7 
8 #ifndef FOLLOW_JOINT_TRAJECTORY_CLIENT_H_
9 #define FOLLOW_JOINT_TRAJECTORY_CLIENT_H_
10 
11 #include <ros/ros.h>
12 #include <control_msgs/JointTrajectoryAction.h>
14 #include <sensor_msgs/JointState.h>
15 #include <trajectory_msgs/JointTrajectory.h>
16 
17 namespace katana_tutorials
18 {
19 
21 
23 {
24 public:
26  virtual ~Pr2JointTrajectoryClient();
27 
28  void startTrajectory(control_msgs::JointTrajectoryGoal goal);
29  control_msgs::JointTrajectoryGoal makeArmUpTrajectory();
31 
32 private:
34  TrajClient traj_client_;
36  std::vector<std::string> joint_names_;
38  std::vector<double> current_joint_state_;
40 
41  void jointStateCB(const sensor_msgs::JointState::ConstPtr &msg);
42 };
43 
44 } /* namespace katana_tutorials */
45 #endif /* FOLLOW_JOINT_TRAJECTORY_CLIENT_H_ */
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > TrajClient
void startTrajectory(control_msgs::JointTrajectoryGoal goal)
Sends the command to start a given trajectory.
control_msgs::JointTrajectoryGoal makeArmUpTrajectory()
actionlib::SimpleClientGoalState getState()
Returns the current state of the action.
void jointStateCB(const sensor_msgs::JointState::ConstPtr &msg)


katana_tutorials
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:41