~guihome/sr-ros-interface/manip-electric_corr4

« back to all changes in this revision

Viewing changes to sr_mechanism_controllers/include/sr_mechanism_controllers/hand_joint_spline_trajectory_action_controller.hpp

  • Committer: guihome at wanadoo
  • Date: 2013-02-14 20:03:45 UTC
  • Revision ID: guihome@wanadoo.fr-20130214200345-2hy6nb3eulz7r3bg
hand_joint_trajectory_action controller was not connecting to correct J0s
Added running2 and reload controllers upgrade to hand_joint_trajectory_action controller

Show diffs side-by-side

added added

removed removed

Lines of Context:
17
17
#include <actionlib/server/simple_action_server.h>
18
18
#include <control_msgs/FollowJointTrajectoryAction.h>
19
19
 
20
 
 
 
20
#include <std_msgs/String.h>
21
21
 
22
22
namespace shadowrobot 
23
23
{
27
27
  public:
28
28
    HandJointTrajectoryActionController();
29
29
    ~HandJointTrajectoryActionController();
 
30
    void setMap();
 
31
    void init();
30
32
 
31
33
  private:
32
34
    ros::NodeHandle nh, nh_tilde;
33
35
    ros::Subscriber command_sub;
 
36
    ros::Subscriber reload_sub;
34
37
    ros::Publisher sr_hand_target_pub;
35
38
    ros::Publisher desired_joint_state_pusblisher;
36
39
    std::vector<std::string> joint_names_;
37
40
    std::vector<std::string> j0labels;          //!< stores J0 joint names for easy access
38
41
    ros::ServiceClient joint_state_client;
39
42
    std::map<std::string,double> joint_state_map;
 
43
    std::vector<std::string> joint_labels;
 
44
    void reload_controllers_callback(const std_msgs::String &command);
 
45
    ros::ServiceClient controller_list_client;
40
46
    
41
47
    std::vector< ros::Publisher > controller_publishers;  //!< This vector stores publishers to each joint controller.
42
48
    std::map<std::string,std::string> jointControllerMap; //!< stores a map of controller name and associated joints