Typedefs | Functions | Variables
usscan Namespace Reference

This namespace groups all typedefs, utility functions and parameter getter used in the simulation_us node. More...

Typedefs

typedef std::shared_ptr< geometry_msgs::Pose > pose_msg_ptr
 shortcut for a pointer to a pose message More...
 
typedef std::shared_ptr< sensor_msgs::Range > scan_msg_ptr
 shortcut for a pointer to a range message More...
 

Functions

void configCallback (pses_simulation::RangeSensorConfig &config, uint32_t level, rs::RangeSensor *sensor, pses_simulation::RangeSensorConfig *dynConfig)
 Sets the RangeSensorConfig object of this sensor simulation. More...
 
void fetchLoopRate (ros::NodeHandle *nh, double &loopRate)
 Get loop rate launch parameter. More...
 
void fetchMapFrameID (ros::NodeHandle *nh, std::string &mapFrameID)
 Get map frame id launch parameter. More...
 
void fetchMapLocation (ros::NodeHandle *nh, std::string &mapLocation)
 Get map location launch parameter. More...
 
void fetchMapMetadataLocation (ros::NodeHandle *nh, std::string &mapMetadataLocation)
 Get map meta data location launch parameter. More...
 
void fetchUSFFrameID (ros::NodeHandle *nh, std::string &usfFrameID)
 Get front ultra sonic sensor frame id launch parameter. More...
 
void fetchUSFTopic (ros::NodeHandle *nh, std::string &usfTopic)
 Get front ultra sonic sensor topic launch parameter. More...
 
void fetchUSLFrameID (ros::NodeHandle *nh, std::string &uslFrameID)
 Get left ultra sonic sensor frame id launch parameter. More...
 
void fetchUSLTopic (ros::NodeHandle *nh, std::string &uslTopic)
 Get left ultra sonic sensor topic launch parameter. More...
 
void fetchUSRFrameID (ros::NodeHandle *nh, std::string &usrFrameID)
 Get right ultra sonic sensor frame id launch parameter. More...
 
void fetchUSRTopic (ros::NodeHandle *nh, std::string &usrTopic)
 Get right ultra sonic sensor topic launch parameter. More...
 
void getPositionInfo (const std::string &base_frame, const std::string &target_frame, const tf::TransformListener &listener, geometry_msgs::Pose *position, std::vector< double > *rpy)
 Get the current postion of a sensor from the tf transformation service. More...
 
cv::Point setGridPosition (geometry_msgs::Pose &sensor, nav_msgs::MapMetaData &mapInfo)
 Calculate the occupancy grid postion of a given pose. More...
 

Variables

static const double DEFAULT_LOOP_RATE = 30.0
 
static const std::string DEFAULT_MAP_FRAME_ID = "map"
 
static const std::string DEFAULT_MAP_LOCATION
 
static const std::string DEFAULT_MAP_METADATA_LOCATION
 
static const std::string DEFAULT_US_FRONT_FRAME_ID = "front_sensor"
 
static const std::string DEFAULT_US_FRONT_TOPIC = "/uc_bridge/usf"
 
static const std::string DEFAULT_US_LEFT_FRAME_ID = "left_sensor"
 
static const std::string DEFAULT_US_LEFT_TOPIC = "/uc_bridge/usl"
 
static const std::string DEFAULT_US_RIGHT_FRAME_ID = "right_sensor"
 
static const std::string DEFAULT_US_RIGHT_TOPIC = "/uc_bridge/usr"
 

Detailed Description

This namespace groups all typedefs, utility functions and parameter getter used in the simulation_us node.

Typedef Documentation

usscan::us::pose_msg_ptr

shortcut for a pointer to a pose message

Definition at line 83 of file simulation_us.cpp.

usscan::us::scan_msg_ptr

shortcut for a pointer to a range message

Definition at line 78 of file simulation_us.cpp.

Function Documentation

void usscan::configCallback ( pses_simulation::RangeSensorConfig &  config,
uint32_t  level,
rs::RangeSensor sensor,
pses_simulation::RangeSensorConfig *  dynConfig 
)

Sets the RangeSensorConfig object of this sensor simulation.

Parameters
[in]configdynamic reconfigure object to reconfigure this sensor
[in]levelunused
[in]sensorcurrent sensor simulation
[out]dynConfigdynamic reconfigure object to reconfigure this sensor

Definition at line 165 of file simulation_us.cpp.

void usscan::fetchLoopRate ( ros::NodeHandle *  nh,
double &  loopRate 
)

Get loop rate launch parameter.

Parameters
[in]nhpointer to a ros::NodeHandle object
[out]loopRateloop rate in Hz

Definition at line 193 of file simulation_us.cpp.

void usscan::fetchMapFrameID ( ros::NodeHandle *  nh,
std::string &  mapFrameID 
)

Get map frame id launch parameter.

Parameters
[in]nhpointer to a ros::NodeHandle object
[out]mapFrameIDcoordinate system id of the map

Definition at line 341 of file simulation_us.cpp.

void usscan::fetchMapLocation ( ros::NodeHandle *  nh,
std::string &  mapLocation 
)

Get map location launch parameter.

Parameters
[in]nhpointer to a ros::NodeHandle object
[out]mapLocationpath to the occupancy grid file (map)

Definition at line 260 of file simulation_us.cpp.

void usscan::fetchMapMetadataLocation ( ros::NodeHandle *  nh,
std::string &  mapMetadataLocation 
)

Get map meta data location launch parameter.

Parameters
[in]nhpointer to a ros::NodeHandle object
[out]mapMetadataLocationpath to the map meta data file

Definition at line 276 of file simulation_us.cpp.

void usscan::fetchUSFFrameID ( ros::NodeHandle *  nh,
std::string &  usfFrameID 
)

Get front ultra sonic sensor frame id launch parameter.

Parameters
[in]nhpointer to a ros::NodeHandle object
[out]usfFrameIDcoordinate system id of this sensor

Definition at line 309 of file simulation_us.cpp.

void usscan::fetchUSFTopic ( ros::NodeHandle *  nh,
std::string &  usfTopic 
)

Get front ultra sonic sensor topic launch parameter.

Parameters
[in]nhpointer to a ros::NodeHandle object
[out]usfTopictopic to which this node publishes sensor information.

Definition at line 227 of file simulation_us.cpp.

void usscan::fetchUSLFrameID ( ros::NodeHandle *  nh,
std::string &  uslFrameID 
)

Get left ultra sonic sensor frame id launch parameter.

Parameters
[in]nhpointer to a ros::NodeHandle object
[out]uslFrameIDcoordinate system id of this sensor

Definition at line 325 of file simulation_us.cpp.

void usscan::fetchUSLTopic ( ros::NodeHandle *  nh,
std::string &  uslTopic 
)

Get left ultra sonic sensor topic launch parameter.

Parameters
[in]nhpointer to a ros::NodeHandle object
[out]uslTopictopic to which this node publishes sensor information.

Definition at line 244 of file simulation_us.cpp.

void usscan::fetchUSRFrameID ( ros::NodeHandle *  nh,
std::string &  usrFrameID 
)

Get right ultra sonic sensor frame id launch parameter.

Parameters
[in]nhpointer to a ros::NodeHandle object
[out]usrFrameIDcoordinate system id of this sensor

Definition at line 293 of file simulation_us.cpp.

void usscan::fetchUSRTopic ( ros::NodeHandle *  nh,
std::string &  usrTopic 
)

Get right ultra sonic sensor topic launch parameter.

Parameters
[in]nhpointer to a ros::NodeHandle object
[out]usrTopictopic to which this node publishes sensor information.

Definition at line 210 of file simulation_us.cpp.

void usscan::getPositionInfo ( const std::string &  base_frame,
const std::string &  target_frame,
const tf::TransformListener &  listener,
geometry_msgs::Pose *  position,
std::vector< double > *  rpy 
)

Get the current postion of a sensor from the tf transformation service.

Parameters
[in]base_frameframe id of the map coordinate system
[in]target_frameframe id of the sensor coordinate system
[in]listenertf transformation service
[out]positioncurrent position of the sensor
[out]rpycurrent orientation of the sensor (0: roll, 1:pitch, 2:yaw)

Definition at line 111 of file simulation_us.cpp.

cv::Point usscan::setGridPosition ( geometry_msgs::Pose &  sensor,
nav_msgs::MapMetaData &  mapInfo 
)

Calculate the occupancy grid postion of a given pose.

Parameters
[in]laserpose message of the sensor
[in]mapInfooccupancy grid meta information
Returns
a point in image coordinates

Definition at line 90 of file simulation_us.cpp.

Variable Documentation

const double usscan::DEFAULT_LOOP_RATE = 30.0
static

Frequency of this simulation.

Definition at line 174 of file simulation_us.cpp.

const std::string usscan::DEFAULT_MAP_FRAME_ID = "map"
static

Coordinate system id of the map

Definition at line 186 of file simulation_us.cpp.

const std::string usscan::DEFAULT_MAP_LOCATION
static
Initial value:
=
ros::package::getPath("pses_simulation") + "/data/map/map.pgm"

Path to the occupancy grid file (map)

Definition at line 178 of file simulation_us.cpp.

const std::string usscan::DEFAULT_MAP_METADATA_LOCATION
static
Initial value:
=
ros::package::getPath("pses_simulation") + "/data/map/map.yaml"

Path to the occupancy grid meta data file

Definition at line 180 of file simulation_us.cpp.

const std::string usscan::DEFAULT_US_FRONT_FRAME_ID = "front_sensor"
static

Coordinate system id of the front sensor

Definition at line 184 of file simulation_us.cpp.

const std::string usscan::DEFAULT_US_FRONT_TOPIC = "/uc_bridge/usf"
static

Topic to which this node publishes front sensor information.

Definition at line 176 of file simulation_us.cpp.

const std::string usscan::DEFAULT_US_LEFT_FRAME_ID = "left_sensor"
static

Coordinate system id of the left sensor

Definition at line 185 of file simulation_us.cpp.

const std::string usscan::DEFAULT_US_LEFT_TOPIC = "/uc_bridge/usl"
static

Topic to which this node publishes left sensor information.

Definition at line 177 of file simulation_us.cpp.

const std::string usscan::DEFAULT_US_RIGHT_FRAME_ID = "right_sensor"
static

Coordinate system id of the right sensor

Definition at line 183 of file simulation_us.cpp.

const std::string usscan::DEFAULT_US_RIGHT_TOPIC = "/uc_bridge/usr"
static

Topic to which this node publishes right sensor information.

Definition at line 175 of file simulation_us.cpp.



pses_simulation
Author(s): Sebastian Ehmes
autogenerated on Wed Dec 13 2017 19:37:54