PowercubeChainNode Class Reference

Implementation of ROS node for powercube_chain. More...

List of all members.

Public Member Functions

void diag_init (diagnostic_updater::DiagnosticStatusWrapper &stat)
void executeCB (const pr2_controllers_msgs::JointTrajectoryGoalConstPtr &goal)
 Executes the callback from the actionlib.
void lock_semaphore (sem_t *sem)
 PowercubeChainNode (std::string name)
 Constructor for PowercubeChainNode class.
void publishJointState ()
 Routine for publishing joint_states.
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_SetDefaultVel (cob_srvs::SetDefaultVel::Request &req, cob_srvs::SetDefaultVel::Response &res)
 Executes the service callback for set_default_vel.
bool srvCallback_SetOperationMode (cob_srvs::SetOperationMode::Request &req, cob_srvs::SetOperationMode::Response &res)
 Executes the service callback for set_operation_mode.
bool srvCallback_Stop (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res)
 Executes the service callback for stop.
void topicCallback_DirectCommand (const trajectory_msgs::JointTrajectory::ConstPtr &msg)
 Executes the callback from the actionlib.
void unlock_semaphore (sem_t *sem)
void updatePCubeCommands ()
 Routine for updating command to the powercubes.
 ~PowercubeChainNode ()
 Destructor for PowercubeChainNode class.

Public Attributes

std::string action_name_
actionlib::SimpleActionServer
< pr2_controllers_msgs::JointTrajectoryAction > 
as_
sem_t * can_sem
int CanBaudrate_
std::string CanDevice_
std::string CanModule_
std::vector< double > cmd_vel_
pr2_controllers_msgs::JointTrajectoryFeedback feedback_
bool finished_
bool isInitialized_
std::vector< std::string > JointNames_
XmlRpc::XmlRpcValue JointNames_param_
std::vector< double > MaxAcc_
XmlRpc::XmlRpcValue MaxAcc_param_
std::vector< int > ModIds_
XmlRpc::XmlRpcValue ModIds_param_
ros::NodeHandle n_
 create a handle for this node, initialize node
bool newvel_
PowerCubeCtrlPCube_
PowerCubeCtrlParamsPCubeParams_
pr2_controllers_msgs::JointTrajectoryResult result_
bool sem_can_available
ros::ServiceServer srvServer_Init_
ros::ServiceServer srvServer_Recover_
ros::ServiceServer srvServer_SetDefaultVel_
ros::ServiceServer srvServer_SetOperationMode_
ros::ServiceServer srvServer_Stop_
ros::Publisher topicPub_ControllerState_
ros::Publisher topicPub_JointState_
ros::Subscriber topicSub_DirectCommand_
trajectory_msgs::JointTrajectory traj_
trajectory_msgs::JointTrajectoryPoint traj_point_
int traj_point_nr_
diagnostic_updater::Updater updater_

Detailed Description

Implementation of ROS node for powercube_chain.

Offers actionlib and direct command interface.

Definition at line 102 of file cob_powercube_chain.cpp.


Constructor & Destructor Documentation

PowercubeChainNode::PowercubeChainNode ( std::string  name  )  [inline]

Constructor for PowercubeChainNode class.

Parameters:
name Name for the actionlib server.

Todo:
: check if yaml parameter file fits to urdf model

Definition at line 162 of file cob_powercube_chain.cpp.

PowercubeChainNode::~PowercubeChainNode (  )  [inline]

Destructor for PowercubeChainNode class.

Definition at line 337 of file cob_powercube_chain.cpp.


Member Function Documentation

void PowercubeChainNode::diag_init ( diagnostic_updater::DiagnosticStatusWrapper &  stat  )  [inline]

Definition at line 357 of file cob_powercube_chain.cpp.

void PowercubeChainNode::executeCB ( const pr2_controllers_msgs::JointTrajectoryGoalConstPtr &  goal  )  [inline]

Executes the callback from the actionlib.

Set the current goal to aborted after receiving a new goal and write new goal to a member variable. Wait for the goal to finish and set actionlib status to succeeded.

Parameters:
goal JointTrajectoryGoal

Definition at line 372 of file cob_powercube_chain.cpp.

void PowercubeChainNode::lock_semaphore ( sem_t *  sem  )  [inline]

Definition at line 144 of file cob_powercube_chain.cpp.

void PowercubeChainNode::publishJointState (  )  [inline]

Routine for publishing joint_states.

Gets current positions and velocities from the hardware and publishes them as joint_states.

Definition at line 565 of file cob_powercube_chain.cpp.

bool PowercubeChainNode::srvCallback_Init ( cob_srvs::Trigger::Request &  req,
cob_srvs::Trigger::Response &  res 
) [inline]

Executes the service callback for init.

Connects to the hardware and initialized it.

Parameters:
req Service request
res Service response

Definition at line 429 of file cob_powercube_chain.cpp.

bool PowercubeChainNode::srvCallback_Recover ( cob_srvs::Trigger::Request &  req,
cob_srvs::Trigger::Response &  res 
) [inline]

Executes the service callback for recover.

Recovers the driver after an emergency stop.

Parameters:
req Service request
res Service response

Definition at line 498 of file cob_powercube_chain.cpp.

bool PowercubeChainNode::srvCallback_SetDefaultVel ( cob_srvs::SetDefaultVel::Request &  req,
cob_srvs::SetDefaultVel::Response &  res 
) [inline]

Executes the service callback for set_default_vel.

Changes the default velocity.

Parameters:
req Service request
res Service response

Definition at line 551 of file cob_powercube_chain.cpp.

bool PowercubeChainNode::srvCallback_SetOperationMode ( cob_srvs::SetOperationMode::Request &  req,
cob_srvs::SetOperationMode::Response &  res 
) [inline]

Executes the service callback for set_operation_mode.

Changes the operation mode.

Parameters:
req Service request
res Service response

Definition at line 535 of file cob_powercube_chain.cpp.

bool PowercubeChainNode::srvCallback_Stop ( cob_srvs::Trigger::Request &  req,
cob_srvs::Trigger::Response &  res 
) [inline]

Executes the service callback for stop.

Stops all hardware movements.

Parameters:
req Service request
res Service response

Definition at line 467 of file cob_powercube_chain.cpp.

void PowercubeChainNode::topicCallback_DirectCommand ( const trajectory_msgs::JointTrajectory::ConstPtr &  msg  )  [inline]

Executes the callback from the actionlib.

Set the current velocity target.

Parameters:
msg JointTrajectory

Definition at line 350 of file cob_powercube_chain.cpp.

void PowercubeChainNode::unlock_semaphore ( sem_t *  sem  )  [inline]

Definition at line 150 of file cob_powercube_chain.cpp.

void PowercubeChainNode::updatePCubeCommands (  )  [inline]

Routine for updating command to the powercubes.

Depending on the operation mode (position/velocity) either position or velocity goals are sent to the hardware.

Definition at line 639 of file cob_powercube_chain.cpp.


Member Data Documentation

Definition at line 106 of file cob_powercube_chain.cpp.

actionlib::SimpleActionServer<pr2_controllers_msgs::JointTrajectoryAction> PowercubeChainNode::as_

Definition at line 105 of file cob_powercube_chain.cpp.

Definition at line 141 of file cob_powercube_chain.cpp.

Definition at line 126 of file cob_powercube_chain.cpp.

Definition at line 125 of file cob_powercube_chain.cpp.

Definition at line 124 of file cob_powercube_chain.cpp.

std::vector<double> PowercubeChainNode::cmd_vel_

Definition at line 135 of file cob_powercube_chain.cpp.

pr2_controllers_msgs::JointTrajectoryFeedback PowercubeChainNode::feedback_

Definition at line 108 of file cob_powercube_chain.cpp.

Definition at line 134 of file cob_powercube_chain.cpp.

Definition at line 133 of file cob_powercube_chain.cpp.

std::vector<std::string> PowercubeChainNode::JointNames_

Definition at line 130 of file cob_powercube_chain.cpp.

Definition at line 129 of file cob_powercube_chain.cpp.

std::vector<double> PowercubeChainNode::MaxAcc_

Definition at line 132 of file cob_powercube_chain.cpp.

XmlRpc::XmlRpcValue PowercubeChainNode::MaxAcc_param_

Definition at line 131 of file cob_powercube_chain.cpp.

std::vector<int> PowercubeChainNode::ModIds_

Definition at line 128 of file cob_powercube_chain.cpp.

XmlRpc::XmlRpcValue PowercubeChainNode::ModIds_param_

Definition at line 127 of file cob_powercube_chain.cpp.

ros::NodeHandle PowercubeChainNode::n_

create a handle for this node, initialize node

Definition at line 88 of file cob_powercube_chain.cpp.

Definition at line 136 of file cob_powercube_chain.cpp.

Definition at line 119 of file cob_powercube_chain.cpp.

Definition at line 123 of file cob_powercube_chain.cpp.

pr2_controllers_msgs::JointTrajectoryResult PowercubeChainNode::result_

Definition at line 109 of file cob_powercube_chain.cpp.

Definition at line 142 of file cob_powercube_chain.cpp.

Definition at line 98 of file cob_powercube_chain.cpp.

Definition at line 100 of file cob_powercube_chain.cpp.

Definition at line 102 of file cob_powercube_chain.cpp.

Definition at line 101 of file cob_powercube_chain.cpp.

Definition at line 99 of file cob_powercube_chain.cpp.

Definition at line 92 of file cob_powercube_chain.cpp.

Definition at line 91 of file cob_powercube_chain.cpp.

Definition at line 95 of file cob_powercube_chain.cpp.

trajectory_msgs::JointTrajectory PowercubeChainNode::traj_

Definition at line 138 of file cob_powercube_chain.cpp.

trajectory_msgs::JointTrajectoryPoint PowercubeChainNode::traj_point_

Definition at line 139 of file cob_powercube_chain.cpp.

Definition at line 140 of file cob_powercube_chain.cpp.

diagnostic_updater::Updater PowercubeChainNode::updater_

Definition at line 112 of file cob_powercube_chain.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


cob_powercube_chain
Author(s): Florian Weisshardt
autogenerated on Fri Jan 11 09:14:23 2013