#include <navigator_internal.h>
Public Member Functions | |
| void | configure () |
| pilot_command_t | navigate (void) |
| Navigator (nav_msgs::Odometry *odom_msg) | |
| void | reduce_speed_with_min (pilot_command_t &pcmd, float new_speed) |
| void | trace_controller (const char *name, pilot_command_t &pcmd) |
| ~Navigator () | |
Public Attributes | |
| Config | config_ |
| Course * | course |
| nav_msgs::Odometry | estimate |
| Estop * | estop |
| art_msgs::NavigatorState | navdata |
| Obstacle * | obstacle |
| nav_msgs::Odometry * | odometry |
| art_msgs::Order | order |
| PolyOps * | pops |
Private Attributes | |
| int | verbose |
Definition at line 64 of file navigator_internal.h.
| Navigator::Navigator | ( | nav_msgs::Odometry * | odom_msg | ) |
Main ART navigator class.
The Navigator class instantiates some infrastructure and the top-level (Estop) controller. Then, on each cycle it runs the Estop controller, which indirectly invokes other controllers when appropriate.
Definition at line 31 of file navigator.cc.
| Navigator::~Navigator | ( | ) |
Definition at line 57 of file navigator.cc.
| void Navigator::configure | ( | ) |
Configure parameters
Definition at line 94 of file navigator.cc.
| pilot_command_t Navigator::navigate | ( | void | ) |
Main navigator entry point -- called once every driver cycle
The order contains a behavior which affects the navigator state for this cycle.
Definition at line 75 of file navigator.cc.
| void Navigator::reduce_speed_with_min | ( | pilot_command_t & | pcmd, | |
| float | new_speed | |||
| ) | [inline] |
Definition at line 92 of file navigator_internal.h.
| void Navigator::trace_controller | ( | const char * | name, | |
| pilot_command_t & | pcmd | |||
| ) | [inline] |
Definition at line 102 of file navigator_internal.h.
Definition at line 89 of file navigator_internal.h.
Definition at line 70 of file navigator_internal.h.
| nav_msgs::Odometry Navigator::estimate |
Definition at line 79 of file navigator_internal.h.
Definition at line 74 of file navigator_internal.h.
| art_msgs::NavigatorState Navigator::navdata |
Definition at line 78 of file navigator_internal.h.
Definition at line 71 of file navigator_internal.h.
| nav_msgs::Odometry* Navigator::odometry |
Definition at line 80 of file navigator_internal.h.
| art_msgs::Order Navigator::order |
Definition at line 77 of file navigator_internal.h.
| PolyOps* Navigator::pops |
Definition at line 69 of file navigator_internal.h.
int Navigator::verbose [private] |
Definition at line 110 of file navigator_internal.h.