Public Member Functions | Public Attributes | List of all members
PowerCubeChainNode Class Reference

Implementation of ROS node for powercube_chain. More...

Public Member Functions

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

Public Attributes

bool error_
 
std::string error_msg_
 
bool initialized_
 member variables More...
 
ros::Time last_publish_time_
 
ros::NodeHandle n_
 create a handle for this node, initialize node More...
 
ros::NodeHandle n_private_
 
PowerCubeCtrlpc_ctrl_
 handle for powercube_chain More...
 
PowerCubeCtrlParamspc_params_
 handle for powercube_chain parameters More...
 
ros::ServiceServer srvServer_Init_
 declaration of service servers More...
 
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 More...
 
ros::Publisher topicPub_OperationMode_
 
ros::Subscriber topicSub_CommandPos_
 declaration of topics to subscribe, callback is called for new messages arriving More...
 
ros::Subscriber topicSub_CommandVel_
 

Detailed Description

Implementation of ROS node for powercube_chain.

Offers velocity and position interface.

Definition at line 51 of file schunk_powercube_chain.cpp.

Constructor & Destructor Documentation

PowerCubeChainNode::PowerCubeChainNode ( )
inline

Constructor.

implementation of topics to publish

implementation of topics to subscribe

implementation of service servers

Definition at line 88 of file schunk_powercube_chain.cpp.

PowerCubeChainNode::~PowerCubeChainNode ( )
inline

Destructor.

Definition at line 118 of file schunk_powercube_chain.cpp.

Member Function Documentation

void PowerCubeChainNode::getRobotDescriptionParameters ( )
inline

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 277 of file schunk_powercube_chain.cpp.

void PowerCubeChainNode::getROSParameters ( )
inline

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 128 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 "control_msgs/JointTrajectoryControllerState"

publishing joint and controller states on topic

Definition at line 577 of file schunk_powercube_chain.cpp.

bool PowerCubeChainNode::srvCallback_Init ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
inline

Executes the service callback for init.

Connects to the hardware and initialized it.

Parameters
reqService request
resService response

initialize powercubes

Definition at line 450 of file schunk_powercube_chain.cpp.

bool PowerCubeChainNode::srvCallback_Recover ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
inline

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 518 of file schunk_powercube_chain.cpp.

bool PowerCubeChainNode::srvCallback_SetOperationMode ( cob_srvs::SetString::Request &  req,
cob_srvs::SetString::Response &  res 
)
inline

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 557 of file schunk_powercube_chain.cpp.

bool PowerCubeChainNode::srvCallback_Stop ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
inline

Executes the service callback for stop.

Stops all hardware movements.

Parameters
reqService request
resService response

stop powercubes

Definition at line 491 of file schunk_powercube_chain.cpp.

void PowerCubeChainNode::topicCallback_CommandPos ( const std_msgs::Float64MultiArray::ConstPtr &  msg)
inline

Executes the callback from the command_pos topic.

Set the current position target.

Parameters
msgFloat64MultiArray

check dimensions

command positions to powercubes

Definition at line 353 of file schunk_powercube_chain.cpp.

void PowerCubeChainNode::topicCallback_CommandVel ( const std_msgs::Float64MultiArray::ConstPtr &  msg)
inline

Executes the callback from the command_vel topic.

Set the current velocity target.

Parameters
msgFloat64MultiArray

check dimensions

command velocities to powercubes

Definition at line 400 of file schunk_powercube_chain.cpp.

Member Data Documentation

bool PowerCubeChainNode::error_

Definition at line 83 of file schunk_powercube_chain.cpp.

std::string PowerCubeChainNode::error_msg_

Definition at line 84 of file schunk_powercube_chain.cpp.

bool PowerCubeChainNode::initialized_

member variables

Definition at line 81 of file schunk_powercube_chain.cpp.

ros::Time PowerCubeChainNode::last_publish_time_

Definition at line 85 of file schunk_powercube_chain.cpp.

ros::NodeHandle PowerCubeChainNode::n_

create a handle for this node, initialize node

Definition at line 55 of file schunk_powercube_chain.cpp.

ros::NodeHandle PowerCubeChainNode::n_private_

Definition at line 56 of file schunk_powercube_chain.cpp.

PowerCubeCtrl* PowerCubeChainNode::pc_ctrl_

handle for powercube_chain

Definition at line 75 of file schunk_powercube_chain.cpp.

PowerCubeCtrlParams* PowerCubeChainNode::pc_params_

handle for powercube_chain parameters

Definition at line 78 of file schunk_powercube_chain.cpp.

ros::ServiceServer PowerCubeChainNode::srvServer_Init_

declaration of service servers

Definition at line 69 of file schunk_powercube_chain.cpp.

ros::ServiceServer PowerCubeChainNode::srvServer_Recover_

Definition at line 72 of file schunk_powercube_chain.cpp.

ros::ServiceServer PowerCubeChainNode::srvServer_SetOperationMode_

Definition at line 70 of file schunk_powercube_chain.cpp.

ros::ServiceServer PowerCubeChainNode::srvServer_Stop_

Definition at line 71 of file schunk_powercube_chain.cpp.

bool PowerCubeChainNode::stopped_

Definition at line 82 of file schunk_powercube_chain.cpp.

ros::Publisher PowerCubeChainNode::topicPub_ControllerState_

Definition at line 60 of file schunk_powercube_chain.cpp.

ros::Publisher PowerCubeChainNode::topicPub_Diagnostic_

Definition at line 62 of file schunk_powercube_chain.cpp.

ros::Publisher PowerCubeChainNode::topicPub_JointState_

declaration of topics to publish

Definition at line 59 of file schunk_powercube_chain.cpp.

ros::Publisher PowerCubeChainNode::topicPub_OperationMode_

Definition at line 61 of file schunk_powercube_chain.cpp.

ros::Subscriber PowerCubeChainNode::topicSub_CommandPos_

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

Definition at line 65 of file schunk_powercube_chain.cpp.

ros::Subscriber PowerCubeChainNode::topicSub_CommandVel_

Definition at line 66 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 Nov 25 2019 03:48:21