Public Member Functions | Public Attributes | Static Public Attributes
youBot::YouBotArmConfiguration Class Reference

#include <YouBotConfiguration.h>

List of all members.

Public Member Functions

 YouBotArmConfiguration ()
 Standard constructor.
virtual ~YouBotArmConfiguration ()
 Standard destructor.

Public Attributes

std::string armID
 "Name" of the arm. Typically derived from name of youBot configuration file.
ros::Publisher armJointStatePublisher
 Publishes JointState messages with angles for the arm.
actionlib::ActionServer
< control_msgs::FollowJointTrajectoryAction > * 
armJointTrajectoryAction
 Implements a "control_msgs/FollowJointTrajectory" action.
ros::Subscriber armPositionCommandSubscriber
 Receives "brics_actuator/JointPositions" for the arm joints.
ros::Subscriber armVelocityCommandSubscriber
 Receives "brics_actuator/JointVelocities" for the arm joints.
ros::ServiceServer calibrateService
 Service to calibrate the arm.
std::string commandTopicName
 Name prefix for topic e.g arm_1/...
std::vector< std::string > gripperFingerNames
 Joint names for the gripper fingers.
ros::Subscriber gripperPositionCommandSubscriber
 Receives "brics_actuator/JointPositions" for the gripper.
std::vector< std::string > jointNames
 Names of the joints. Are typically derived from the configuration files.
double lastGripperCommand
std::string parentFrameIDName
 Parent frameID for the published messages.
ros::ServiceServer switchOffMotorsService
 Service to switch the motor off by setting the PWM value to zero.
ros::ServiceServer switchONMotorsService
 Service to switch the motor ON by setting the velocity to zero.
youbot::YouBotManipulator * youBotArm
 Handle to the arm.

Static Public Attributes

static const unsigned int LEFT_FINGER_INDEX = 0
static const unsigned int RIGHT_FINGER_INDEX = 1

Detailed Description

Definition at line 103 of file YouBotConfiguration.h.


Constructor & Destructor Documentation

Standard constructor.

Definition at line 76 of file YouBotConfiguration.cpp.

Standard destructor.

Definition at line 94 of file YouBotConfiguration.cpp.


Member Data Documentation

"Name" of the arm. Typically derived from name of youBot configuration file.

Definition at line 118 of file YouBotConfiguration.h.

Publishes JointState messages with angles for the arm.

Definition at line 149 of file YouBotConfiguration.h.

Implements a "control_msgs/FollowJointTrajectory" action.

Definition at line 142 of file YouBotConfiguration.h.

Receives "brics_actuator/JointPositions" for the arm joints.

Definition at line 136 of file YouBotConfiguration.h.

Receives "brics_actuator/JointVelocities" for the arm joints.

Definition at line 139 of file YouBotConfiguration.h.

Service to calibrate the arm.

Definition at line 158 of file YouBotConfiguration.h.

Name prefix for topic e.g arm_1/...

Definition at line 121 of file YouBotConfiguration.h.

Joint names for the gripper fingers.

Definition at line 130 of file YouBotConfiguration.h.

Receives "brics_actuator/JointPositions" for the gripper.

Definition at line 145 of file YouBotConfiguration.h.

Names of the joints. Are typically derived from the configuration files.

Definition at line 127 of file YouBotConfiguration.h.

This variable memorizes the last successfully set value for the gripper, so it can be published in the joint state message. This is necessary at the moment, as it is not yet possible to measure the actual distance. Consider the gripper joint state as an open loop value.

Definition at line 169 of file YouBotConfiguration.h.

const unsigned int youBot::YouBotArmConfiguration::LEFT_FINGER_INDEX = 0 [static]

Definition at line 132 of file YouBotConfiguration.h.

Parent frameID for the published messages.

Definition at line 124 of file YouBotConfiguration.h.

const unsigned int youBot::YouBotArmConfiguration::RIGHT_FINGER_INDEX = 1 [static]

Definition at line 133 of file YouBotConfiguration.h.

Service to switch the motor off by setting the PWM value to zero.

Definition at line 152 of file YouBotConfiguration.h.

Service to switch the motor ON by setting the velocity to zero.

Definition at line 155 of file YouBotConfiguration.h.

youbot::YouBotManipulator* youBot::YouBotArmConfiguration::youBotArm

Handle to the arm.

Definition at line 114 of file YouBotConfiguration.h.


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


youbot_driver_ros_interface
Author(s): Sebastian Blumenthal
autogenerated on Thu Jun 6 2019 20:43:35