Public Member Functions | |
bool | build_graph () |
CommanderNode () | |
bool | parse_args (int argc, char **argv) |
void | print_usage (int argc, char **argv) |
void | processNavState (const art_msgs::NavigatorState::ConstPtr &nst) |
void | putOrder (const art_msgs::Order &order) |
bool | setup (ros::NodeHandle node) |
bool | spin () |
bool | wait_for_input () |
~CommanderNode () | |
Private Attributes | |
std::string | frame_id_ |
frame ID of map (default "/map") | |
Graph * | graph_ |
bool | load_mission_ |
MDF * | mdf_ |
std::string | mdf_name_ |
Mission * | mission_ |
std::string | mission_file_ |
ros::Publisher | nav_cmd_pub_ |
ros::Subscriber | nav_state_topic_ |
art_msgs::NavigatorState | navState_ |
RNDF * | rndf_ |
std::string | rndf_name_ |
double | speed_limit_ |
bool | startrun_ |
int | verbose_ |
ZonePerimeterList | zones_ |
Commander node class.
Definition at line 76 of file ros_node.cc.
CommanderNode::CommanderNode | ( | ) | [inline] |
Definition at line 79 of file ros_node.cc.
CommanderNode::~CommanderNode | ( | ) | [inline] |
Definition at line 130 of file ros_node.cc.
bool CommanderNode::build_graph | ( | ) | [inline] |
Build road map graph
Definition at line 198 of file ros_node.cc.
bool CommanderNode::parse_args | ( | int | argc, | |
char ** | argv | |||
) | [inline] |
Parse command line arguments
Definition at line 162 of file ros_node.cc.
void CommanderNode::print_usage | ( | int | argc, | |
char ** | argv | |||
) | [inline] |
Print command argument usage message
Definition at line 323 of file ros_node.cc.
void CommanderNode::processNavState | ( | const art_msgs::NavigatorState::ConstPtr & | nst | ) | [inline] |
Process navigator state input
Definition at line 155 of file ros_node.cc.
void CommanderNode::putOrder | ( | const art_msgs::Order & | order | ) | [inline] |
Send order in command to navigator driver
Definition at line 256 of file ros_node.cc.
bool CommanderNode::setup | ( | ros::NodeHandle | node | ) | [inline] |
Set up ROS topics
Definition at line 141 of file ros_node.cc.
bool CommanderNode::spin | ( | ) | [inline] |
Main spin loop
Definition at line 268 of file ros_node.cc.
bool CommanderNode::wait_for_input | ( | ) | [inline] |
Wait for navigator state message to arrive
Definition at line 337 of file ros_node.cc.
std::string CommanderNode::frame_id_ [private] |
frame ID of map (default "/map")
Definition at line 364 of file ros_node.cc.
Graph* CommanderNode::graph_ [private] |
Definition at line 373 of file ros_node.cc.
bool CommanderNode::load_mission_ [private] |
Definition at line 358 of file ros_node.cc.
MDF* CommanderNode::mdf_ [private] |
Definition at line 372 of file ros_node.cc.
std::string CommanderNode::mdf_name_ [private] |
Definition at line 362 of file ros_node.cc.
Mission* CommanderNode::mission_ [private] |
Definition at line 374 of file ros_node.cc.
std::string CommanderNode::mission_file_ [private] |
Definition at line 357 of file ros_node.cc.
ros::Publisher CommanderNode::nav_cmd_pub_ [private] |
Definition at line 368 of file ros_node.cc.
ros::Subscriber CommanderNode::nav_state_topic_ [private] |
Definition at line 367 of file ros_node.cc.
art_msgs::NavigatorState CommanderNode::navState_ [private] |
Definition at line 369 of file ros_node.cc.
RNDF* CommanderNode::rndf_ [private] |
Definition at line 371 of file ros_node.cc.
std::string CommanderNode::rndf_name_ [private] |
Definition at line 361 of file ros_node.cc.
double CommanderNode::speed_limit_ [private] |
Definition at line 360 of file ros_node.cc.
bool CommanderNode::startrun_ [private] |
Definition at line 359 of file ros_node.cc.
int CommanderNode::verbose_ [private] |
Definition at line 363 of file ros_node.cc.
ZonePerimeterList CommanderNode::zones_ [private] |
Definition at line 375 of file ros_node.cc.