Revision e4bb9fd4
| examples/meka/include/mekajointinterface.h | ||
|---|---|---|
| 10 | 10 | 
     | 
| 11 | 11 | 
    class MekaJointInterface : public humotion::server::JointInterface{
   | 
| 12 | 12 | 
    public:  | 
| 13 | 
    MekaJointInterface(std::string scope);  | 
|
| 13 | 
        MekaJointInterface(std::string _input_scope, std::string _output_scope);
   | 
|
| 14 | 14 | 
    ~MekaJointInterface();  | 
| 15 | 15 | 
     | 
| 16 | 16 | 
    //void fetch_position(Device *dev, double timestamp);  | 
| ... | ... | |
| 74 | 74 | 
    int lid_opening_previous;  | 
| 75 | 75 | 
    int previous_mouth_state;  | 
| 76 | 76 | 
     | 
| 77 | 
    std::string scope;  | 
|
| 77 | 
    std::string input_scope;  | 
|
| 78 | 
    std::string output_scope;  | 
|
| 78 | 79 | 
     | 
| 79 | 80 | 
    float last_pos_eye_vergence;  | 
| 80 | 81 | 
    float last_pos_eye_pan;  | 
| examples/meka/src/mekajointinterface.cpp | ||
|---|---|---|
| 55 | 55 | 
    }  | 
| 56 | 56 | 
     | 
| 57 | 57 | 
    //! constructor  | 
| 58 | 
    MekaJointInterface::MekaJointInterface(string _scope) : humotion::server::JointInterface(){
   | 
|
| 59 | 
    scope = _scope;  | 
|
| 60 | 
    string js_topic = scope + "/joint_states";  | 
|
| 61 | 
    string target_topic = scope + "/meka_roscontrol/head_position_trajectory_controller/command";  | 
|
| 58 | 
    MekaJointInterface::MekaJointInterface(string _input_scope, string _output_scope) : humotion::server::JointInterface(){
   | 
|
| 59 | 
    input_scope = _input_scope;  | 
|
| 60 | 
    output_scope = _output_scope;  | 
|
| 62 | 61 | 
     | 
| 63 | 62 | 
    //subscribe to meka joint states  | 
| 64 | 63 | 
    int argc = 0;  | 
| ... | ... | |
| 66 | 65 | 
    ros::NodeHandle n;  | 
| 67 | 66 | 
     | 
| 68 | 67 | 
     | 
| 69 | 
        printf("> listening on jointstates on '%s'\n",js_topic.c_str());
   | 
|
| 70 | 
        joint_state_subscriber = n.subscribe(js_topic, 150, &MekaJointInterface::incoming_jointstates , this);
   | 
|
| 68 | 
        printf("> listening on jointstates on '%s'\n",input_scope.c_str());
   | 
|
| 69 | 
        joint_state_subscriber = n.subscribe(input_scope, 150, &MekaJointInterface::incoming_jointstates , this);
   | 
|
| 71 | 70 | 
     | 
| 72 | 
        printf("> sending targets on '%s'\n", target_topic.c_str());
   | 
|
| 73 | 
        target_publisher = n.advertise<trajectory_msgs::JointTrajectory>(target_topic, 100);
   | 
|
| 71 | 
        printf("> sending targets on '%s'\n", output_scope.c_str());
   | 
|
| 72 | 
        target_publisher = n.advertise<trajectory_msgs::JointTrajectory>(output_scope, 100);
   | 
|
| 74 | 73 | 
     | 
| 75 | 74 | 
     | 
| 76 | 75 | 
    //tell humotion about min/max joint values:  | 
Also available in: Unified diff