Public Member Functions | Private Member Functions | Private Attributes
PathFollower Class Reference

List of all members.

Public Member Functions

bool getRobotPose (tf::StampedTransform &globalToBase, const std::string &global_frame_id)
void goalActionCB (const move_base_msgs::MoveBaseGoalConstPtr &goal)
void goalCB (const geometry_msgs::PoseStampedConstPtr &goal)
void pathActionCB (const nao_msgs::FollowPathGoalConstPtr &goal)
void pathCB (const nav_msgs::PathConstPtr &goal)
 PathFollower ()
 ~PathFollower ()

Private Member Functions

void footContactCallback (const std_msgs::BoolConstPtr &contact)
bool getNextTarget (const nav_msgs::Path &path, const tf::Pose &robotPose, const std::vector< geometry_msgs::PoseStamped >::const_iterator &currentPathPoseIt, tf::Stamped< tf::Transform > &targetPose, std::vector< geometry_msgs::PoseStamped >::const_iterator &targetPathPoseIt)
void publishTargetPoseVis (const tf::Stamped< tf::Pose > &targetPose)
 Publishes the target pose as a geometry_msgs/Pose for visualization.
void setVelocity (const tf::Transform &relTarget)
 Velocity controller.
void stopWalk ()
 Stop walk and uninhibit joystick.

Private Attributes

ros::Publisher m_actionGoalPub
ros::Publisher m_actionPathPub
std::string m_baseFrameId
 Base frame of the robot.
double m_controllerFreq
 Desired frequency for controller loop.
bool m_footContact
 True = robot currently has foot contact with the ground.
ros::Subscriber m_footContactSub
ros::ServiceClient m_inhibitWalkClient
bool m_isJoystickInhibited
 True = joystick walk commands are inhibited.
const double m_maxStepFreq
 Maximum step frequency (2.38 Hz according to Nao documentation).
double m_maxVelFractionX
 Maximum fraction of forward velocity for velocity controller, between 0.0 and 1.0.
double m_maxVelFractionY
 Maximum fraction of sideways velocity for velocity controller, between 0.0 and 1.0.
double m_maxVelFractionYaw
 Maximum fraction of rotational velocity for velocity controller, between 0.0 and 1.0.
const double m_maxVelXY
 Maximum translational velocity (0.0952 m/s according to Nao documentation).
const double m_maxVelYaw
 Maximum rotational velocity (47.6 deg/s according to Nao documentation).
const double m_minStepFreq
 Minimum step frequency (1.67 Hz according to Nao documentation).
double m_pathNextTargetDistance
 Cumulative Distance to next Velocity Target from current robot pose along path.
ros::Subscriber m_simpleGoalSub
ros::Subscriber m_simplePathSub
double m_stepFactor
 Fraction of the maximum step frequency.
double m_stepFreq
 Step frequency (should be set to the same value as in nao_walker).
double m_targetAngThres
 Maximum angular deviation from target orientation.
double m_targetDistThres
 Maximum linear deviation from target point.
ros::Publisher m_targetPub
tf::TransformListener m_tfListener
double m_thresholdDampXY
 Slow down when distance to goal is smaller than this value [in meters].
double m_thresholdDampYaw
 Slow down rotation when angular deviation from goal pose is smaller than this value [in radians].
double m_thresholdFar
double m_thresholdRotate
ros::ServiceClient m_uninhibitWalkClient
bool m_useFootContactProtection
 True = abort walk when robot is lifted off the ground.
bool m_useVelocityController
 True = use simple velocity controller, false = use Aldebaran's walkTo controller.
ros::Publisher m_velPub
ros::Publisher m_visPub
actionlib::SimpleActionServer
< move_base_msgs::MoveBaseAction
m_walkGoalServer
actionlib::SimpleActionServer
< nao_msgs::FollowPathAction > 
m_walkPathServer
ros::NodeHandle nh
ros::NodeHandle privateNh

Detailed Description

Definition at line 50 of file nao_path_follower.cpp.


Constructor & Destructor Documentation

Definition at line 105 of file nao_path_follower.cpp.

Definition at line 175 of file nao_path_follower.cpp.


Member Function Documentation

void PathFollower::footContactCallback ( const std_msgs::BoolConstPtr &  contact) [private]

Definition at line 210 of file nao_path_follower.cpp.

bool PathFollower::getNextTarget ( const nav_msgs::Path &  path,
const tf::Pose robotPose,
const std::vector< geometry_msgs::PoseStamped >::const_iterator &  currentPathPoseIt,
tf::Stamped< tf::Transform > &  targetPose,
std::vector< geometry_msgs::PoseStamped >::const_iterator &  targetPathPoseIt 
) [private]

Definition at line 311 of file nao_path_follower.cpp.

bool PathFollower::getRobotPose ( tf::StampedTransform globalToBase,
const std::string &  global_frame_id 
)

Definition at line 227 of file nao_path_follower.cpp.

Definition at line 687 of file nao_path_follower.cpp.

void PathFollower::goalCB ( const geometry_msgs::PoseStampedConstPtr &  goal)

Definition at line 193 of file nao_path_follower.cpp.

void PathFollower::pathActionCB ( const nao_msgs::FollowPathGoalConstPtr &  goal)

Definition at line 450 of file nao_path_follower.cpp.

void PathFollower::pathCB ( const nav_msgs::PathConstPtr &  goal)

Definition at line 201 of file nao_path_follower.cpp.

void PathFollower::publishTargetPoseVis ( const tf::Stamped< tf::Pose > &  targetPose) [private]

Publishes the target pose as a geometry_msgs/Pose for visualization.

Parameters:
targetPoseTarget pose to publish.

Definition at line 187 of file nao_path_follower.cpp.

void PathFollower::setVelocity ( const tf::Transform relTarget) [private]

Velocity controller.

Parameters:
relTargetTarget pose relative to the current robot pose.

Strategy:

distance            | angle               | strategy
-----------------------------------------------------------------
> m_thresholdFar    | > m_thresholdRotate | rotate on the spot towards the target
> m_thresholdFar    | < m_thresholdRotate | walk towards the target, orient towards the target
> m_targetDistThres |                     | walk towards the target, orient towards final yaw angle
< m_targetDistThres | > m_targetAngThres  | rotate on the spot towards final yaw angle
< m_targetDistThres | < m_targetAngThres  | stop

Definition at line 862 of file nao_path_follower.cpp.

void PathFollower::stopWalk ( ) [private]

Stop walk and uninhibit joystick.

Definition at line 813 of file nao_path_follower.cpp.


Member Data Documentation

Definition at line 71 of file nao_path_follower.cpp.

Definition at line 71 of file nao_path_follower.cpp.

std::string PathFollower::m_baseFrameId [private]

Base frame of the robot.

Definition at line 78 of file nao_path_follower.cpp.

Desired frequency for controller loop.

Definition at line 79 of file nao_path_follower.cpp.

True = robot currently has foot contact with the ground.

Definition at line 84 of file nao_path_follower.cpp.

Definition at line 76 of file nao_path_follower.cpp.

Definition at line 75 of file nao_path_follower.cpp.

True = joystick walk commands are inhibited.

Definition at line 82 of file nao_path_follower.cpp.

const double PathFollower::m_maxStepFreq [private]

Maximum step frequency (2.38 Hz according to Nao documentation).

Definition at line 96 of file nao_path_follower.cpp.

Maximum fraction of forward velocity for velocity controller, between 0.0 and 1.0.

Definition at line 88 of file nao_path_follower.cpp.

Maximum fraction of sideways velocity for velocity controller, between 0.0 and 1.0.

Definition at line 89 of file nao_path_follower.cpp.

Maximum fraction of rotational velocity for velocity controller, between 0.0 and 1.0.

Definition at line 90 of file nao_path_follower.cpp.

const double PathFollower::m_maxVelXY [private]

Maximum translational velocity (0.0952 m/s according to Nao documentation).

Definition at line 93 of file nao_path_follower.cpp.

const double PathFollower::m_maxVelYaw [private]

Maximum rotational velocity (47.6 deg/s according to Nao documentation).

Definition at line 94 of file nao_path_follower.cpp.

const double PathFollower::m_minStepFreq [private]

Minimum step frequency (1.67 Hz according to Nao documentation).

Definition at line 95 of file nao_path_follower.cpp.

Cumulative Distance to next Velocity Target from current robot pose along path.

Definition at line 102 of file nao_path_follower.cpp.

Definition at line 70 of file nao_path_follower.cpp.

Definition at line 70 of file nao_path_follower.cpp.

double PathFollower::m_stepFactor [private]

Fraction of the maximum step frequency.

Definition at line 92 of file nao_path_follower.cpp.

double PathFollower::m_stepFreq [private]

Step frequency (should be set to the same value as in nao_walker).

Definition at line 91 of file nao_path_follower.cpp.

Maximum angular deviation from target orientation.

Definition at line 81 of file nao_path_follower.cpp.

Maximum linear deviation from target point.

Definition at line 80 of file nao_path_follower.cpp.

Definition at line 71 of file nao_path_follower.cpp.

Definition at line 72 of file nao_path_follower.cpp.

Slow down when distance to goal is smaller than this value [in meters].

Definition at line 99 of file nao_path_follower.cpp.

Slow down rotation when angular deviation from goal pose is smaller than this value [in radians].

Definition at line 100 of file nao_path_follower.cpp.

double PathFollower::m_thresholdFar [private]
See also:
PathFollower::setVelocity()

Definition at line 97 of file nao_path_follower.cpp.

See also:
PathFollower::setVelocity()

Definition at line 98 of file nao_path_follower.cpp.

Definition at line 75 of file nao_path_follower.cpp.

True = abort walk when robot is lifted off the ground.

Definition at line 83 of file nao_path_follower.cpp.

True = use simple velocity controller, false = use Aldebaran's walkTo controller.

Definition at line 87 of file nao_path_follower.cpp.

Definition at line 71 of file nao_path_follower.cpp.

Definition at line 71 of file nao_path_follower.cpp.

Definition at line 73 of file nao_path_follower.cpp.

actionlib::SimpleActionServer<nao_msgs::FollowPathAction> PathFollower::m_walkPathServer [private]

Definition at line 74 of file nao_path_follower.cpp.

Definition at line 68 of file nao_path_follower.cpp.

Definition at line 69 of file nao_path_follower.cpp.


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


nao_remote
Author(s): Armin Hornung
autogenerated on Sat Oct 26 2013 11:02:42