jog_frame_node.h
Go to the documentation of this file.
1 #ifndef JOG_FRAME_H
2 #define JOG_FRAME_H
3 
4 #include <string>
5 #include <ros/ros.h>
6 #include <tf/tf.h>
7 #include <jog_msgs/JogFrame.h>
8 #include <sensor_msgs/JointState.h>
12 #include <moveit_msgs/GetPositionFK.h>
13 #include <moveit_msgs/GetPositionIK.h>
14 #include <control_msgs/FollowJointTrajectoryAction.h>
16 #include <trajectory_msgs/JointTrajectoryPoint.h>
17 
19 
20 namespace jog_frame
21 {
22 
23 typedef struct
24 {
25 public:
26  std::string action_ns;
27  std::string type;
28  std::vector<std::string> joints;
29 
30 } Controller;
31 
36 {
37 public:
41  JogFrameNode ();
42  void jog_frame_cb (jog_msgs::JogFrameConstPtr msg);
43  void joint_state_cb (sensor_msgs::JointStateConstPtr msg);
44  int get_controller_list();
45 
46 protected:
49 
50  std::map<std::string, Controller> cinfo_map_;
51  std::map<std::string, TrajClient*> traj_clients_;
52  std::map<std::string,ros::Publisher> traj_pubs_;
53 
54  std::map<std::string, double> joint_map_;
55  geometry_msgs::PoseStamped pose_stamped_;
56 
60 
61  std::string target_link_;
62  std::string group_name_;
63  std::vector<std::string> exclude_joints_;
64  sensor_msgs::JointState joint_state_;
66 };
67 
68 } // namespace jog_frame
69 
70 #endif // JOG_FRAME_NODE_H
msg
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > TrajClient
ros::ServiceClient ik_client_
ros::Subscriber jog_frame_sub_
std::map< std::string, double > joint_map_
void jog_frame_cb(jog_msgs::JogFrameConstPtr msg)
Callback function for the topic jog_frame.
geometry_msgs::PoseStamped pose_stamped_
void joint_state_cb(sensor_msgs::JointStateConstPtr msg)
Callback function for the topic joint_state.
ros::ServiceClient fk_client_
std::map< std::string, Controller > cinfo_map_
ros::Subscriber joint_state_sub_
std::map< std::string, ros::Publisher > traj_pubs_
std::vector< std::string > joints
std::vector< std::string > exclude_joints_
sensor_msgs::JointState joint_state_
std::map< std::string, TrajClient * > traj_clients_


jog_controller
Author(s): Ryosuke Tajima
autogenerated on Sun May 17 2020 03:25:01