Functions | Variables
link_joints.cpp File Reference
#include <ros/ros.h>
#include <string>
#include <std_msgs/Float64.h>
#include <control_msgs/JointControllerState.h>
Include dependency graph for link_joints.cpp:

Go to the source code of this file.

Functions

void callback (const control_msgs::JointControllerStateConstPtr &msg)
 
int main (int argc, char **argv)
 

Variables

std::string child_name = "rh_mfj3"
 the name of the child joint to link to the parent More...
 
std::string controller_type = "_position_controller"
 Controller that controls joint position. More...
 
std::string parent_name = "rh_ffj3"
 the name of the parent joint More...
 
ros::Publisher pub
 
ros::Subscriber sub
 

Detailed Description

Author
Ugo Cupcic ugo@s.nosp@m.hado.nosp@m.wrobo.nosp@m.t.co.nosp@m.m, Contact conta.nosp@m.ct@s.nosp@m.hadow.nosp@m.robo.nosp@m.t.com
Date
Thu Jul 8 16:57:22 2010

Copyright 2011 Shadow Robot Company Ltd.

This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation version 2 of the License.

This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.

You should have received a copy of the GNU General Public License along with this program. If not, see http://www.gnu.org/licenses/.

This example demonstrates how two joints can have their positions 'linked' by having a child joint subscribing to the parent joint's controller state topic. The messages are then published to the child joint's controller.

The hand should be launched but the trajectory controllers should not be running as they overwrite position commands. To check if they are, a call to rosservice can be made with the following command: >rosservice call /controller_manager/list_controllers To stop the trajectory controllers, open the gui (type rqt) and select position control in plugins > Shadow Robot > Change controllers NOTE: If the joint sliders plugin is open during this change of controllers, it will need to be reloaded.

A position can then be published to the parent joint or the joint could be moved by using the joint sliders in the gui, plugins > Shadow Robot > joint slider

If you move the joint slider for FFJ3, then MFJ3 will move as well.

Definition in file link_joints.cpp.

Function Documentation

void callback ( const control_msgs::JointControllerStateConstPtr &  msg)

The callback function is called each time a message is received on the controller

Parameters
msgmessage of type sr_hand::joints_data

Definition at line 65 of file link_joints.cpp.

int main ( int  argc,
char **  argv 
)

The main: initialise a ros node, a subscriber and a publisher

Parameters
argc
argv
Returns
0 on success

init the subscriber and subscribe to the parent joint controller topic using the callback function callback()

init the publisher on the child joint controller command topic publishing messages of the type std_msgs::Float64.

Definition at line 83 of file link_joints.cpp.

Variable Documentation

std::string child_name = "rh_mfj3"

the name of the child joint to link to the parent

Definition at line 50 of file link_joints.cpp.

std::string controller_type = "_position_controller"

Controller that controls joint position.

Definition at line 52 of file link_joints.cpp.

std::string parent_name = "rh_ffj3"

the name of the parent joint

Definition at line 48 of file link_joints.cpp.

Definition at line 57 of file link_joints.cpp.

Definition at line 55 of file link_joints.cpp.



sr_example
Author(s): Ugo Cupcic
autogenerated on Wed Oct 14 2020 04:05:12