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

List of all members.

Public Member Functions

 NavQueueMgr ()
bool setup (ros::NodeHandle node)
bool shutdown ()
void spin (void)
 ~NavQueueMgr ()

Private Member Functions

void processNavCmd (const art_msgs::NavigatorCommand::ConstPtr &cmdIn)
void processOdom (const nav_msgs::Odometry::ConstPtr &odomIn)
void processRelays (const art_msgs::IOadrState::ConstPtr &sigIn)
void processRoadMap (const art_msgs::ArtLanes::ConstPtr &cmdIn)
void PublishState (void)
void reconfig (Config &newconfig, uint32_t level)
void SetRelays (void)
void SetSpeed (pilot_command_t pcmd)

Private Attributes

bool alarm_on_
ros::Publisher car_cmd_
dynamic_reconfigure::Server
< Config
ccb_
ros::Time cmd_time_
bool flasher_on_
ros::Time map_time_
Navigatornav_
ros::Subscriber nav_cmd_
ros::Publisher nav_state_
nav_msgs::Odometry odom_msg_
ros::Subscriber odom_state_
ros::Subscriber roadmap_
bool signal_on_left_
bool signal_on_right_
ros::Publisher signals_cmd_
ros::Subscriber signals_state_

Detailed Description

Definition at line 44 of file queue_mgr.cc.


Constructor & Destructor Documentation

constructor

Definition at line 102 of file queue_mgr.cc.

Definition at line 50 of file queue_mgr.cc.


Member Function Documentation

Handle command input.

Definition at line 113 of file queue_mgr.cc.

void NavQueueMgr::processOdom ( const nav_msgs::Odometry::ConstPtr &  odomIn) [private]

Handle Odometry input.

Definition at line 123 of file queue_mgr.cc.

Handle relays state message.

Definition at line 147 of file queue_mgr.cc.

void NavQueueMgr::processRoadMap ( const art_msgs::ArtLanes::ConstPtr mapIn) [private]

Handle road map polygons.

Definition at line 139 of file queue_mgr.cc.

void NavQueueMgr::PublishState ( void  ) [private]

Publish current navigator state data

Definition at line 323 of file queue_mgr.cc.

void NavQueueMgr::reconfig ( Config newconfig,
uint32_t  level 
) [private]

handle dynamic reconfigure service request

Parameters:
newconfignew configuration from dynamic reconfigure client, becomes the service reply message as updated here.
levelSensorLevels value (0xffffffff on initial call)

This is done without any locking because it is called in the same thread as ros::spinOnce() and the topic subscription callbacks.

Definition at line 190 of file queue_mgr.cc.

void NavQueueMgr::SetRelays ( void  ) [private]

Set or reset relays

Precondition:
signal_on_left_, signal_on_right_, flasher_on_ and alarm_on_ reflect the most recently reported states of those relays;
nav_->navdata contains desired signal relay states

Definition at line 249 of file queue_mgr.cc.

void NavQueueMgr::SetSpeed ( pilot_command_t  pcmd) [private]

Send a command to the pilot

Definition at line 296 of file queue_mgr.cc.

Set up ROS topics for navigator node

Definition at line 198 of file queue_mgr.cc.

Definition at line 224 of file queue_mgr.cc.

void NavQueueMgr::spin ( void  )

Spin method for main thread

Definition at line 345 of file queue_mgr.cc.


Member Data Documentation

Definition at line 85 of file queue_mgr.cc.

Definition at line 71 of file queue_mgr.cc.

dynamic_reconfigure::Server<Config> NavQueueMgr::ccb_ [private]

Definition at line 98 of file queue_mgr.cc.

Definition at line 91 of file queue_mgr.cc.

Definition at line 84 of file queue_mgr.cc.

Definition at line 92 of file queue_mgr.cc.

Definition at line 95 of file queue_mgr.cc.

Definition at line 72 of file queue_mgr.cc.

Definition at line 73 of file queue_mgr.cc.

nav_msgs::Odometry NavQueueMgr::odom_msg_ [private]

Definition at line 88 of file queue_mgr.cc.

Definition at line 74 of file queue_mgr.cc.

Definition at line 75 of file queue_mgr.cc.

Definition at line 82 of file queue_mgr.cc.

Definition at line 83 of file queue_mgr.cc.

Definition at line 76 of file queue_mgr.cc.

Definition at line 77 of file queue_mgr.cc.


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


art_nav
Author(s): Austin Robot Technology, Jack O'Quin
autogenerated on Tue Sep 24 2013 10:42:11