This namespace groups all typedefs, utility functions and parameter getter used in the simulation_laser 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::LaserScan > | scan_msg_ptr | 
| shortcut for a pointer to a laser scan 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 | fetchLaserscanFrameID (ros::NodeHandle *nh, std::string &laserscanFrameID) | 
| Get laser scan frame id launch parameter.  More... | |
| void | fetchLaserScanTopic (ros::NodeHandle *nh, std::string &laserScanTopic) | 
| Get laser scan topic launch parameter.  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 | 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 &laser, nav_msgs::MapMetaData &mapInfo) | 
| Calculate the occupancy grid postion of a given pose.  More... | |
Variables | |
| static const std::string | DEFAULT_LASER_SCAN_TOPIC | 
| static const std::string | DEFAULT_LASERSCAN_FRAME_ID | 
| static const double | DEFAULT_LOOP_RATE | 
| static const std::string | DEFAULT_MAP_FRAME_ID | 
| static const std::string | DEFAULT_MAP_LOCATION | 
| static const std::string | DEFAULT_MAP_METADATA_LOCATION | 
This namespace groups all typedefs, utility functions and parameter getter used in the simulation_laser node.
shortcut for a pointer to a pose message
Definition at line 84 of file simulation_laser.cpp.
shortcut for a pointer to a laser scan message
Definition at line 79 of file simulation_laser.cpp.
| void laserscan::configCallback | ( | pses_simulation::RangeSensorConfig & | config, | 
| uint32_t | level, | ||
| rs::RangeSensor * | sensor, | ||
| pses_simulation::RangeSensorConfig * | dynConfig | ||
| ) | 
Sets the RangeSensorConfig object of this sensor simulation.
| [in] | config | dynamic reconfigure object to reconfigure this sensor | 
| [in] | level | unused | 
| [in] | sensor | current sensor simulation | 
| [out] | dynConfig | dynamic reconfigure object to reconfigure this sensor | 
Definition at line 166 of file simulation_laser.cpp.
| void laserscan::fetchLaserscanFrameID | ( | ros::NodeHandle * | nh, | 
| std::string & | laserscanFrameID | ||
| ) | 
Get laser scan frame id launch parameter.
| [in] | nh | pointer to a ros::NodeHandle object | 
| [out] | laserscanFrameID | coordinate system id of this sensor | 
Definition at line 262 of file simulation_laser.cpp.
| void laserscan::fetchLaserScanTopic | ( | ros::NodeHandle * | nh, | 
| std::string & | laserScanTopic | ||
| ) | 
Get laser scan topic launch parameter.
| [in] | nh | pointer to a ros::NodeHandle object | 
| [out] | laserScanTopic | topic to which this node publishes sensor information. | 
Definition at line 213 of file simulation_laser.cpp.
| void laserscan::fetchLoopRate | ( | ros::NodeHandle * | nh, | 
| double & | loopRate | ||
| ) | 
Get loop rate launch parameter.
| [in] | nh | pointer to a ros::NodeHandle object | 
| [out] | loopRate | loop rate in Hz | 
Definition at line 196 of file simulation_laser.cpp.
| void laserscan::fetchMapFrameID | ( | ros::NodeHandle * | nh, | 
| std::string & | mapFrameID | ||
| ) | 
Get map frame id launch parameter.
| [in] | nh | pointer to a ros::NodeHandle object | 
| [out] | mapFrameID | coordinate system id of the map | 
Definition at line 278 of file simulation_laser.cpp.
| void laserscan::fetchMapLocation | ( | ros::NodeHandle * | nh, | 
| std::string & | mapLocation | ||
| ) | 
Get map location launch parameter.
| [in] | nh | pointer to a ros::NodeHandle object | 
| [out] | mapLocation | path to the occupancy grid file (map) | 
Definition at line 229 of file simulation_laser.cpp.
| void laserscan::fetchMapMetadataLocation | ( | ros::NodeHandle * | nh, | 
| std::string & | mapMetadataLocation | ||
| ) | 
Get map meta data location launch parameter.
| [in] | nh | pointer to a ros::NodeHandle object | 
| [out] | mapMetadataLocation | path to the map meta data file | 
Definition at line 245 of file simulation_laser.cpp.
| void laserscan::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.
| [in] | base_frame | frame id of the map coordinate system | 
| [in] | target_frame | frame id of the sensor coordinate system | 
| [in] | listener | tf transformation service | 
| [out] | position | current position of the sensor | 
| [out] | rpy | current orientation of the sensor (0: roll, 1:pitch, 2:yaw) | 
Definition at line 112 of file simulation_laser.cpp.
| cv::Point laserscan::setGridPosition | ( | geometry_msgs::Pose & | laser, | 
| nav_msgs::MapMetaData & | mapInfo | ||
| ) | 
Calculate the occupancy grid postion of a given pose.
| [in] | laser | pose message of the sensor | 
| [in] | mapInfo | occupancy grid meta information | 
Definition at line 92 of file simulation_laser.cpp.
      
  | 
  static | 
Topic to which this node publishes sensor information.
Definition at line 177 of file simulation_laser.cpp.
      
  | 
  static | 
Coordinate system id of this sensor
Definition at line 186 of file simulation_laser.cpp.
      
  | 
  static | 
Frequency of this simulation.
Definition at line 175 of file simulation_laser.cpp.
      
  | 
  static | 
Coordinate system id of the map
Definition at line 188 of file simulation_laser.cpp.
      
  | 
  static | 
Path to the occupancy grid file (map)
Definition at line 180 of file simulation_laser.cpp.
      
  | 
  static | 
Path to the occupancy grid meta data file
Definition at line 183 of file simulation_laser.cpp.