Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
lama_jockeys::NavigatingJockey Class Reference

#include <navigating_jockey.h>

Inheritance diagram for lama_jockeys::NavigatingJockey:
Inheritance graph
[legend]

List of all members.

Public Member Functions

double get_kp_v ()
double get_kp_w ()
double get_max_goal_distance ()
double get_max_goal_dtheta ()
double get_min_velocity ()
double get_reach_distance ()
void set_kp_v (double val)
void set_kp_w (double val)
void set_max_goal_distance (double d)
void set_max_goal_dtheta (double d)
void set_min_velocity (double val)
void set_reach_distance (double d)

Protected Member Functions

virtual geometry_msgs::Twist goToGoal (const geometry_msgs::Point &goal)
void initAction ()
bool isGoalReached ()
 NavigatingJockey (const std::string &name)
virtual void onContinue ()
virtual void onInterrupt ()
virtual void onStop ()=0
virtual void onTraverse ()=0
void setGoalReached ()
void unsetGoalReached ()

Protected Attributes

lama_jockeys::NavigateFeedback feedback_
lama_jockeys::NavigateGoal goal_
lama_jockeys::NavigateResult result_
NavigateServer server_

Private Member Functions

void goalCallback (const lama_jockeys::NavigateGoalConstPtr &goal)
void preemptCallback ()

Private Attributes

bool goal_reached_
double kp_v_
 Proportional gain for the linear velocity (s^-1).
double kp_w_
 Proportional gain for the angular velocity (s^-1).
double max_goal_distance_
 If the goal is farther than this distance, stop the robot.
double max_goal_dtheta_
 The goal angular distance will be limited to this.
double min_velocity_
 Minimum set velocity (m.s^-1)
double reach_distance_
 Goal is reached if closer than this (m).

Detailed Description

Definition at line 27 of file navigating_jockey.h.


Constructor & Destructor Documentation

lama_jockeys::NavigatingJockey::NavigatingJockey ( const std::string &  name) [protected]

Definition at line 6 of file navigating_jockey.cpp.


Member Function Documentation

Definition at line 37 of file navigating_jockey.h.

Definition at line 40 of file navigating_jockey.h.

Definition at line 31 of file navigating_jockey.h.

Definition at line 34 of file navigating_jockey.h.

Definition at line 43 of file navigating_jockey.h.

Definition at line 46 of file navigating_jockey.h.

void lama_jockeys::NavigatingJockey::goalCallback ( const lama_jockeys::NavigateGoalConstPtr &  goal) [private]

Definition at line 30 of file navigating_jockey.cpp.

geometry_msgs::Twist lama_jockeys::NavigatingJockey::goToGoal ( const geometry_msgs::Point goal) [protected, virtual]

Return the twist to reach the given goal pose

There is no cycle in this function, so it should be called periodically by class instances.

goal[in] position of the goal relative to the robot

Definition at line 104 of file navigating_jockey.cpp.

Reimplemented from lama_jockeys::Jockey.

Definition at line 82 of file navigating_jockey.cpp.

bool lama_jockeys::NavigatingJockey::isGoalReached ( ) [inline, protected]

Definition at line 66 of file navigating_jockey.h.

void lama_jockeys::NavigatingJockey::onContinue ( ) [protected, virtual]

Reimplemented from lama_jockeys::Jockey.

Definition at line 93 of file navigating_jockey.cpp.

void lama_jockeys::NavigatingJockey::onInterrupt ( ) [protected, virtual]

Reimplemented from lama_jockeys::Jockey.

Definition at line 88 of file navigating_jockey.cpp.

virtual void lama_jockeys::NavigatingJockey::onStop ( ) [protected, pure virtual]
virtual void lama_jockeys::NavigatingJockey::onTraverse ( ) [protected, pure virtual]

Definition at line 75 of file navigating_jockey.cpp.

void lama_jockeys::NavigatingJockey::set_kp_v ( double  val) [inline]

Definition at line 38 of file navigating_jockey.h.

void lama_jockeys::NavigatingJockey::set_kp_w ( double  val) [inline]

Definition at line 41 of file navigating_jockey.h.

Definition at line 32 of file navigating_jockey.h.

Definition at line 35 of file navigating_jockey.h.

void lama_jockeys::NavigatingJockey::set_min_velocity ( double  val) [inline]

Definition at line 44 of file navigating_jockey.h.

Definition at line 47 of file navigating_jockey.h.

void lama_jockeys::NavigatingJockey::setGoalReached ( ) [inline, protected]

Definition at line 64 of file navigating_jockey.h.

Definition at line 65 of file navigating_jockey.h.


Member Data Documentation

lama_jockeys::NavigateFeedback lama_jockeys::NavigatingJockey::feedback_ [protected]

Definition at line 72 of file navigating_jockey.h.

lama_jockeys::NavigateGoal lama_jockeys::NavigatingJockey::goal_ [protected]

Definition at line 77 of file navigating_jockey.h.

Definition at line 88 of file navigating_jockey.h.

Proportional gain for the linear velocity (s^-1).

Definition at line 91 of file navigating_jockey.h.

Proportional gain for the angular velocity (s^-1).

Definition at line 92 of file navigating_jockey.h.

If the goal is farther than this distance, stop the robot.

Definition at line 89 of file navigating_jockey.h.

The goal angular distance will be limited to this.

Definition at line 90 of file navigating_jockey.h.

Minimum set velocity (m.s^-1)

Definition at line 93 of file navigating_jockey.h.

Goal is reached if closer than this (m).

Definition at line 94 of file navigating_jockey.h.

lama_jockeys::NavigateResult lama_jockeys::NavigatingJockey::result_ [protected]

Definition at line 71 of file navigating_jockey.h.

Definition at line 70 of file navigating_jockey.h.


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


jockeys
Author(s): Gaël Ecorchard , Karel Košnar
autogenerated on Sat Jun 8 2019 19:03:15