Public Member Functions | Public Attributes
PowerCubeChainNode Class Reference

Implementation of ROS node for powercube_chain. More...

List of all members.

Public Member Functions

void getRobotDescriptionParameters ()
 Gets parameters from the robot_description and configures the powercube_chain.
void getROSParameters ()
 Gets parameters from the ROS parameter server and configures the powercube_chain.
 PowerCubeChainNode ()
 Constructor.
void publishState (bool update=true)
 Publishes the state of the powercube_chain as ros messages.
bool srvCallback_Init (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res)
 Executes the service callback for init.
bool srvCallback_Recover (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res)
 Executes the service callback for recover.
bool srvCallback_SetOperationMode (cob_srvs::SetOperationMode::Request &req, cob_srvs::SetOperationMode::Response &res)
 Executes the service callback for SetOperationMode.
bool srvCallback_Stop (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res)
 Executes the service callback for stop.
void topicCallback_CommandPos (const brics_actuator::JointPositions::ConstPtr &msg)
 Executes the callback from the command_pos topic.
void topicCallback_CommandVel (const brics_actuator::JointVelocities::ConstPtr &msg)
 Executes the callback from the command_vel topic.
 ~PowerCubeChainNode ()
 Destructor.

Public Attributes

bool error_
std::string error_msg_
bool initialized_
 member variables
ros::Time last_publish_time_
ros::NodeHandle n_
 create a handle for this node, initialize node
PowerCubeCtrlpc_ctrl_
 handle for powercube_chain
PowerCubeCtrlParamspc_params_
 handle for powercube_chain parameters
ros::ServiceServer srvServer_Init_
 declaration of service servers
ros::ServiceServer srvServer_Recover_
ros::ServiceServer srvServer_SetOperationMode_
ros::ServiceServer srvServer_Stop_
bool stopped_
ros::Publisher topicPub_ControllerState_
ros::Publisher topicPub_Diagnostic_
ros::Publisher topicPub_JointState_
 declaration of topics to publish
ros::Publisher topicPub_OperationMode_
ros::Subscriber topicSub_CommandPos_
 declaration of topics to subscribe, callback is called for new messages arriving
ros::Subscriber topicSub_CommandVel_

Detailed Description

Implementation of ROS node for powercube_chain.

Offers velocity and position interface.

Definition at line 94 of file schunk_powercube_chain.cpp.


Constructor & Destructor Documentation

Constructor.

implementation of topics to publish

implementation of topics to subscribe

implementation of service servers

Definition at line 131 of file schunk_powercube_chain.cpp.

Destructor.

Definition at line 161 of file schunk_powercube_chain.cpp.


Member Function Documentation

Gets parameters from the robot_description and configures the powercube_chain.

Get robot_description from ROS parameter server

Get urdf model out of robot_description

Get max velocities out of urdf model

Get lower limits out of urdf model

Get offsets out of urdf model

Set parameters

Definition at line 327 of file schunk_powercube_chain.cpp.

Gets parameters from the ROS parameter server and configures the powercube_chain.

get CanModule

get CanDevice

get CanBaudrate

get Modul IDs

get force_use_movevel

Resize and assign of values to the ModulIDs

Initialize parameters

Get joint names

Resize and assign of values to the JointNames

Check dimension with with DOF

Get max accelerations

Resize and assign of values to the MaxAccelerations

Check dimension with with DOF

Get horizon

Horizon in sec

Definition at line 171 of file schunk_powercube_chain.cpp.

void PowerCubeChainNode::publishState ( bool  update = true) [inline]

Publishes the state of the powercube_chain as ros messages.

Published to "/joint_states" as "sensor_msgs/JointState" Published to "state" as "pr2_controllers_msgs/JointTrajectoryState"

publishing joint and controller states on topic

Definition at line 621 of file schunk_powercube_chain.cpp.

Executes the service callback for init.

Connects to the hardware and initialized it.

Parameters:
reqService request
resService response

initialize powercubes

Definition at line 494 of file schunk_powercube_chain.cpp.

Executes the service callback for recover.

Recovers the driver after an emergency stop.

Parameters:
reqService request
resService response

stopping all arm movements

Definition at line 562 of file schunk_powercube_chain.cpp.

Executes the service callback for SetOperationMode.

Sets the driver to different operation modes. Currently only operation_mode=velocity is supported.

Parameters:
reqService request
resService response

Definition at line 601 of file schunk_powercube_chain.cpp.

Executes the service callback for stop.

Stops all hardware movements.

Parameters:
reqService request
resService response

stop powercubes

Definition at line 535 of file schunk_powercube_chain.cpp.

Executes the callback from the command_pos topic.

Set the current position target.

Parameters:
msgJointPositions

Definition at line 405 of file schunk_powercube_chain.cpp.

Executes the callback from the command_vel topic.

Set the current velocity target.

Parameters:
msgJointVelocities

ToDo: don't rely on position of joint names, but merge them (check between msg.joint_uri and member variable JointStates)

check dimensions

parse velocities

check joint name

check unit

if all checks are successful, parse the velocity value for this joint

command velocities to powercubes

Definition at line 416 of file schunk_powercube_chain.cpp.


Member Data Documentation

Definition at line 126 of file schunk_powercube_chain.cpp.

Definition at line 127 of file schunk_powercube_chain.cpp.

member variables

Definition at line 124 of file schunk_powercube_chain.cpp.

Definition at line 128 of file schunk_powercube_chain.cpp.

create a handle for this node, initialize node

Definition at line 99 of file schunk_powercube_chain.cpp.

handle for powercube_chain

Definition at line 118 of file schunk_powercube_chain.cpp.

handle for powercube_chain parameters

Definition at line 121 of file schunk_powercube_chain.cpp.

declaration of service servers

Definition at line 112 of file schunk_powercube_chain.cpp.

Definition at line 115 of file schunk_powercube_chain.cpp.

Definition at line 113 of file schunk_powercube_chain.cpp.

Definition at line 114 of file schunk_powercube_chain.cpp.

Definition at line 125 of file schunk_powercube_chain.cpp.

Definition at line 103 of file schunk_powercube_chain.cpp.

Definition at line 105 of file schunk_powercube_chain.cpp.

declaration of topics to publish

Definition at line 102 of file schunk_powercube_chain.cpp.

Definition at line 104 of file schunk_powercube_chain.cpp.

declaration of topics to subscribe, callback is called for new messages arriving

Definition at line 108 of file schunk_powercube_chain.cpp.

Definition at line 109 of file schunk_powercube_chain.cpp.


The documentation for this class was generated from the following file:


schunk_powercube_chain
Author(s): Florian Weisshardt
autogenerated on Mon Oct 6 2014 07:31:10