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

List of all members.

Public Member Functions

bool buildRoadMap (void)
 MapLanesDriver ()
int Setup (ros::NodeHandle node)
int Shutdown (void)
void Spin (void)
 ~MapLanesDriver ()

Private Member Functions

void markCar ()
 create marker for car pose.
void processOdom (const nav_msgs::Odometry::ConstPtr &odomIn)
void publishGlobalMap (void)
void publishLocalMap (void)
void publishMapCloud (ros::Publisher &pub, const art_msgs::ArtLanes &lane_data)
 Publish map point cloud.
void publishMapMarks (ros::Publisher &pub, const std::string &map_name, ros::Duration life, const art_msgs::ArtLanes &lane_data)
 Publish map visualization markers.

Private Attributes

ros::Publisher car_image_
sensor_msgs::PointCloud cloud_msg_
std::string frame_id_
 frame ID of map (default "/map")
Graphgraph_
 graph object (used by MapLanes)
bool initial_position_
 true if initial odometry received
MapLanesmap_
 MapLanes object instance.
ros::Publisher mapmarks_
visualization_msgs::MarkerArray marks_msg_
nav_msgs::Odometry odom_msg_
ros::Subscriber odom_topic_
double poly_size_
 maximum polygon size (m)
double range_
 radius of local lanes to report (m)
std::string rndf_name_
 Road Network Definition File name.
ros::Publisher roadmap_cloud_
ros::Publisher roadmap_global_
ros::Publisher roadmap_local_

Detailed Description

ROS node class for road map driver.

Definition at line 55 of file mapl.cc.


Constructor & Destructor Documentation

constructor

Definition at line 117 of file mapl.cc.

Definition at line 61 of file mapl.cc.


Member Function Documentation

Build road map

Returns:
true if successful

Definition at line 509 of file mapl.cc.

void MapLanesDriver::markCar ( ) [private]

create marker for car pose.

Parameters:
pubtopic to publish
markersarray to add car pose

Definition at line 158 of file mapl.cc.

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

Handle odometry input

Definition at line 241 of file mapl.cc.

void MapLanesDriver::publishGlobalMap ( void  ) [private]

Publish global road map

Definition at line 434 of file mapl.cc.

void MapLanesDriver::publishLocalMap ( void  ) [private]

Publish current local road map

Definition at line 457 of file mapl.cc.

void MapLanesDriver::publishMapCloud ( ros::Publisher pub,
const art_msgs::ArtLanes lane_data 
) [private]

Publish map point cloud.

Converts polygon data into point cloud for clearing the occupancy grid.

Parameters:
pubtopic to publish
lane_datapolygons to publish

Definition at line 259 of file mapl.cc.

void MapLanesDriver::publishMapMarks ( ros::Publisher pub,
const std::string &  map_name,
ros::Duration  life,
const art_msgs::ArtLanes lane_data 
) [private]

Publish map visualization markers.

Converts polygon data into an array of rviz visualization markers.

Parameters:
pubtopic to publish
map_namemarker namespace
lifelifespan for these markers
lane_datapolygons to publish
Note:
Do not to send too much information to rviz every cycle. If it gets behind displaying them, it becomes unusable.

Definition at line 304 of file mapl.cc.

Set up ROS topics

Definition at line 199 of file mapl.cc.

int MapLanesDriver::Shutdown ( void  )

Shutdown the driver

Definition at line 233 of file mapl.cc.

void MapLanesDriver::Spin ( void  )

Spin function for driver thread

Definition at line 484 of file mapl.cc.


Member Data Documentation

Definition at line 99 of file mapl.cc.

Definition at line 105 of file mapl.cc.

std::string MapLanesDriver::frame_id_ [private]

frame ID of map (default "/map")

Definition at line 90 of file mapl.cc.

graph object (used by MapLanes)

Definition at line 111 of file mapl.cc.

true if initial odometry received

Definition at line 113 of file mapl.cc.

MapLanes object instance.

Definition at line 112 of file mapl.cc.

Definition at line 98 of file mapl.cc.

visualization_msgs::MarkerArray MapLanesDriver::marks_msg_ [private]

Definition at line 109 of file mapl.cc.

nav_msgs::Odometry MapLanesDriver::odom_msg_ [private]

Definition at line 94 of file mapl.cc.

Definition at line 93 of file mapl.cc.

double MapLanesDriver::poly_size_ [private]

maximum polygon size (m)

Definition at line 88 of file mapl.cc.

double MapLanesDriver::range_ [private]

radius of local lanes to report (m)

Definition at line 87 of file mapl.cc.

std::string MapLanesDriver::rndf_name_ [private]

Road Network Definition File name.

Definition at line 89 of file mapl.cc.

Definition at line 101 of file mapl.cc.

Definition at line 96 of file mapl.cc.

Definition at line 97 of file mapl.cc.


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


art_map
Author(s): David Li, Patrick Beeson, Bartley Gillen, Tarun Nimmagadda, Mickey Ristroph, Michael Quinlan, Jack O'Quin
autogenerated on Fri Jan 3 2014 11:08:34