All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines
Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Static Private Attributes
youBot::YouBotOODLWrapper Class Reference

Wrapper class to map ROS messages to OODL method calls for the youBot platform. More...

#include <YouBotOODLWrapper.h>

List of all members.

Public Member Functions

void armCommandCallback (const trajectory_msgs::JointTrajectory &youbotArmCommand)
 Callback that is executed when a commend for the arm comes in.
void armJointTrajectoryCancelCallback (actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction >::GoalHandle youbotArmGoal, unsigned int armIndex)
 Callback that is executed when an action goal of a joint trajectory is canceled.
void armJointTrajectoryGoalCallback (actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction >::GoalHandle youbotArmGoal, unsigned int armIndex)
 Callback that is executed when an action goal to perform a joint trajectory with the arm comes in.
void armPositionsCommandCallback (const brics_actuator::JointPositionsConstPtr &youbotArmCommand, int armIndex)
 Callback that is executed when a position command for the arm comes in.
void armVelocitiesCommandCallback (const brics_actuator::JointVelocitiesConstPtr &youbotArmCommand, int armIndex)
 Callback that is executed when a velocity command for the arm comes in.
void baseCommandCallback (const geometry_msgs::Twist &youbotBaseCommand)
 Callback that is executed when a commend for the base comes in.
bool calibrateArmCallback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response, int armIndex)
void computeOODLSensorReadings ()
 Mapps OODL values to ROS messages.
void gripperPositionsCommandCallback (const brics_actuator::JointPositionsConstPtr &youbotGripperCommand, int armIndex)
 Callback that is executed when a position command for the gripper comes in.
void initializeArm (std::string armName, bool enableStandardGripper=true)
 Initializes a youBot base.
void initializeBase (std::string baseName)
 Initializes a youBot base.
void publishArmAndBaseDiagnostics (double publish_rate_in_secs)
 Publishes status of base and arm as diagnostic and dashboard messages continuously.
void publishOODLSensorReadings ()
 Publishes all sensor measurements. Both for base and arm.
bool reconnectCallback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
void stop ()
 Stops all initialized elements. Stops arm and/or base (if initialized).
bool switchOffArmMotorsCallback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response, int armIndex)
bool switchOffBaseMotorsCallback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
bool switchOnArmMotorsCallback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response, int armIndex)
bool switchOnBaseMotorsCallback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 YouBotOODLWrapper (ros::NodeHandle n)
 Constructor with a ROS handle.
virtual ~YouBotOODLWrapper ()
 DEfault constructor.

Public Attributes

YouBotConfiguration youBotConfiguration
 Handle the aggregates all parts of a youBot system.

Private Member Functions

 YouBotOODLWrapper ()

Private Attributes

bool areArmMotorsSwitchedOn
bool areBaseMotorsSwitchedOn
actionlib::ActionServer
< control_msgs::FollowJointTrajectoryAction >
::GoalHandle 
armActiveJointTrajectoryGoal
 The joint trajectory goal that is currently active.
bool armHasActiveJointTrajectoryGoal
 Tell if a goal is currently active.
vector< sensor_msgs::JointState > armJointStateMessages
 Vector of the published joint states of per arm with angles in [RAD].
sensor_msgs::JointState baseJointStateMessage
 The published joint state of the base (wheels) with angles in [RAD] and velocities in [RAD/s].
ros::Time currentTime
 ROS timestamp.
ros::Publisher dashboardMessagePublisher
diagnostic_msgs::DiagnosticArray diagnosticArrayMessage
ros::Publisher diagnosticArrayPublisher
std::string diagnosticNameArms
std::string diagnosticNameBase
diagnostic_msgs::DiagnosticStatus diagnosticStatusMessage
youbot::GripperSensedBarPosition gripperBar1Position
youbot::GripperSensedBarPosition gripperBar2Position
int gripperCycleCounter
ros::Time lastDiagnosticPublishTime
 diagnostic msgs
ros::NodeHandle node
 The ROS node handle.
nav_msgs::Odometry odometryMessage
 The published odometry message with distances in [m], angles in [RAD] and velocities in [m/s] and [RAD/s].
geometry_msgs::Quaternion odometryQuaternion
 The quaternion inside the tf odometry frame with distances in [m].
geometry_msgs::TransformStamped odometryTransform
 The published odometry tf frame with distances in [m].
youbot_oodl::PowerBoardState platformStateMessage
std::string youBotArmFrameID
std::string youBotChildFrameID
double youBotDriverCycleFrequencyInHz
std::string youBotOdometryChildFrameID
std::string youBotOdometryFrameID

Static Private Attributes

static const int youBotArmDoF = 5
 Degrees of freedom for the youBot manipulator.
static const int youBotNumberOfFingers = 2
 Number of finger mounted on the gripper.
static const int youBotNumberOfWheels = 4
 Number of wheels attached to the base.

Detailed Description

Wrapper class to map ROS messages to OODL method calls for the youBot platform.

Definition at line 78 of file YouBotOODLWrapper.h.


Constructor & Destructor Documentation

Constructor with a ROS handle.

Parameters:
nROS handle

Definition at line 53 of file YouBotOODLWrapper.cpp.

DEfault constructor.

Definition at line 76 of file YouBotOODLWrapper.cpp.

Definition at line 49 of file YouBotOODLWrapper.cpp.


Member Function Documentation

void youBot::YouBotOODLWrapper::armCommandCallback ( const trajectory_msgs::JointTrajectory &  youbotArmCommand)

Callback that is executed when a commend for the arm comes in.

Deprecated:
Parameters:
youbotArmCommandMessage that contains the desired joint configuration.

Currently only the first configuration (JointTrajectoryPoint) per message is processed. Velocity and acceleration values are ignored.

void youBot::YouBotOODLWrapper::armJointTrajectoryCancelCallback ( actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction >::GoalHandle  youbotArmGoal,
unsigned int  armIndex 
)

Callback that is executed when an action goal of a joint trajectory is canceled.

Parameters:
youbotArmGoalActionlib goal that contains the trajectory.
armIndexIndex that identifies the arm

Definition at line 667 of file YouBotOODLWrapper.cpp.

void youBot::YouBotOODLWrapper::armJointTrajectoryGoalCallback ( actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction >::GoalHandle  youbotArmGoal,
unsigned int  armIndex 
)

Callback that is executed when an action goal to perform a joint trajectory with the arm comes in.

Parameters:
youbotArmGoalActionlib goal that contains the trajectory.
armIndexIndex that identifies the arm

Definition at line 549 of file YouBotOODLWrapper.cpp.

void youBot::YouBotOODLWrapper::armPositionsCommandCallback ( const brics_actuator::JointPositionsConstPtr &  youbotArmCommand,
int  armIndex 
)

Callback that is executed when a position command for the arm comes in.

Parameters:
youbotArmCommandMessage that contains the desired joint configuration.
armIndexIndex that identifies the arm

Definition at line 402 of file YouBotOODLWrapper.cpp.

void youBot::YouBotOODLWrapper::armVelocitiesCommandCallback ( const brics_actuator::JointVelocitiesConstPtr &  youbotArmCommand,
int  armIndex 
)

Callback that is executed when a velocity command for the arm comes in.

Parameters:
youbotArmCommandMessage that contains the desired joint configuration.
armIndexIndex that identifies the arm

Definition at line 475 of file YouBotOODLWrapper.cpp.

void youBot::YouBotOODLWrapper::baseCommandCallback ( const geometry_msgs::Twist &  youbotBaseCommand)

Callback that is executed when a commend for the base comes in.

Parameters:
youbotBaseCommandMessage that contains the desired translational and rotational velocity for the base.

Definition at line 353 of file YouBotOODLWrapper.cpp.

bool youBot::YouBotOODLWrapper::calibrateArmCallback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response,
int  armIndex 
)

Definition at line 1178 of file YouBotOODLWrapper.cpp.

Mapps OODL values to ROS messages.

Definition at line 786 of file YouBotOODLWrapper.cpp.

void youBot::YouBotOODLWrapper::gripperPositionsCommandCallback ( const brics_actuator::JointPositionsConstPtr &  youbotGripperCommand,
int  armIndex 
)

Callback that is executed when a position command for the gripper comes in.

Parameters:
youbotGripperCommandMessage that contains the desired joint configuration.
armIndexIndex that identifies the arm

Definition at line 698 of file YouBotOODLWrapper.cpp.

void youBot::YouBotOODLWrapper::initializeArm ( std::string  armName,
bool  enableStandardGripper = true 
)

Initializes a youBot base.

Parameters:
armNameName of the base. Used to open the configuration file e.g. youbot-manipulator.cfg
enableStandardGripperIf set to true, then the default gripper of the youBot will be initialized.

Definition at line 125 of file YouBotOODLWrapper.cpp.

void youBot::YouBotOODLWrapper::initializeBase ( std::string  baseName)

Initializes a youBot base.

Parameters:
baseNameName of the base. Used to open the configuration file e.g. youbot-base.cfg

Definition at line 83 of file YouBotOODLWrapper.cpp.

void youBot::YouBotOODLWrapper::publishArmAndBaseDiagnostics ( double  publish_rate_in_secs)

Publishes status of base and arm as diagnostic and dashboard messages continuously.

Definition at line 1248 of file YouBotOODLWrapper.cpp.

Publishes all sensor measurements. Both for base and arm.

Depending on what has been initialized before, either odometry and/or joint state valiues are published. computeOODLSensorReadings needs to be executed before.

Definition at line 1014 of file YouBotOODLWrapper.cpp.

bool youBot::YouBotOODLWrapper::reconnectCallback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)

Definition at line 1206 of file YouBotOODLWrapper.cpp.

Stops all initialized elements. Stops arm and/or base (if initialized).

Definition at line 310 of file YouBotOODLWrapper.cpp.

bool youBot::YouBotOODLWrapper::switchOffArmMotorsCallback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response,
int  armIndex 
)

Definition at line 1104 of file YouBotOODLWrapper.cpp.

bool youBot::YouBotOODLWrapper::switchOffBaseMotorsCallback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)

Definition at line 1035 of file YouBotOODLWrapper.cpp.

bool youBot::YouBotOODLWrapper::switchOnArmMotorsCallback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response,
int  armIndex 
)

Definition at line 1141 of file YouBotOODLWrapper.cpp.

bool youBot::YouBotOODLWrapper::switchOnBaseMotorsCallback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)

Definition at line 1069 of file YouBotOODLWrapper.cpp.


Member Data Documentation

Definition at line 278 of file YouBotOODLWrapper.h.

Definition at line 277 of file YouBotOODLWrapper.h.

actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction>::GoalHandle youBot::YouBotOODLWrapper::armActiveJointTrajectoryGoal [private]

The joint trajectory goal that is currently active.

Definition at line 249 of file YouBotOODLWrapper.h.

Tell if a goal is currently active.

Definition at line 252 of file YouBotOODLWrapper.h.

vector<sensor_msgs::JointState> youBot::YouBotOODLWrapper::armJointStateMessages [private]

Vector of the published joint states of per arm with angles in [RAD].

Definition at line 246 of file YouBotOODLWrapper.h.

sensor_msgs::JointState youBot::YouBotOODLWrapper::baseJointStateMessage [private]

The published joint state of the base (wheels) with angles in [RAD] and velocities in [RAD/s].

Definition at line 243 of file YouBotOODLWrapper.h.

ROS timestamp.

Definition at line 231 of file YouBotOODLWrapper.h.

Definition at line 268 of file YouBotOODLWrapper.h.

diagnostic_msgs::DiagnosticArray youBot::YouBotOODLWrapper::diagnosticArrayMessage [private]

Definition at line 272 of file YouBotOODLWrapper.h.

Definition at line 271 of file YouBotOODLWrapper.h.

Definition at line 274 of file YouBotOODLWrapper.h.

Definition at line 275 of file YouBotOODLWrapper.h.

diagnostic_msgs::DiagnosticStatus youBot::YouBotOODLWrapper::diagnosticStatusMessage [private]

Definition at line 273 of file YouBotOODLWrapper.h.

youbot::GripperSensedBarPosition youBot::YouBotOODLWrapper::gripperBar1Position [private]

Definition at line 254 of file YouBotOODLWrapper.h.

youbot::GripperSensedBarPosition youBot::YouBotOODLWrapper::gripperBar2Position [private]

Definition at line 255 of file YouBotOODLWrapper.h.

Definition at line 256 of file YouBotOODLWrapper.h.

diagnostic msgs

Definition at line 266 of file YouBotOODLWrapper.h.

The ROS node handle.

Definition at line 228 of file YouBotOODLWrapper.h.

nav_msgs::Odometry youBot::YouBotOODLWrapper::odometryMessage [private]

The published odometry message with distances in [m], angles in [RAD] and velocities in [m/s] and [RAD/s].

Definition at line 234 of file YouBotOODLWrapper.h.

geometry_msgs::Quaternion youBot::YouBotOODLWrapper::odometryQuaternion [private]

The quaternion inside the tf odometry frame with distances in [m].

Definition at line 240 of file YouBotOODLWrapper.h.

geometry_msgs::TransformStamped youBot::YouBotOODLWrapper::odometryTransform [private]

The published odometry tf frame with distances in [m].

Definition at line 237 of file YouBotOODLWrapper.h.

youbot_oodl::PowerBoardState youBot::YouBotOODLWrapper::platformStateMessage [private]

Definition at line 269 of file YouBotOODLWrapper.h.

const int youBot::YouBotOODLWrapper::youBotArmDoF = 5 [static, private]

Degrees of freedom for the youBot manipulator.

Definition at line 214 of file YouBotOODLWrapper.h.

Definition at line 225 of file YouBotOODLWrapper.h.

Definition at line 222 of file YouBotOODLWrapper.h.

Handle the aggregates all parts of a youBot system.

Definition at line 207 of file YouBotOODLWrapper.h.

Definition at line 263 of file YouBotOODLWrapper.h.

const int youBot::YouBotOODLWrapper::youBotNumberOfFingers = 2 [static, private]

Number of finger mounted on the gripper.

Definition at line 217 of file YouBotOODLWrapper.h.

const int youBot::YouBotOODLWrapper::youBotNumberOfWheels = 4 [static, private]

Number of wheels attached to the base.

Definition at line 220 of file YouBotOODLWrapper.h.

Definition at line 224 of file YouBotOODLWrapper.h.

Definition at line 223 of file YouBotOODLWrapper.h.


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


youbot_oodl
Author(s): Sebastian Blumenthal
autogenerated on Fri Jul 26 2013 12:00:42