Implementation simulation_us ros node. More...
#include <ros/ros.h>#include <ros/package.h>#include <geometry_msgs/TransformStamped.h>#include <nav_msgs/MapMetaData.h>#include <tf/transform_listener.h>#include <string>#include <vector>#include <sensor_msgs/Range.h>#include <yaml-cpp/yaml.h>#include <pses_simulation/RangeSensor.h>#include <dynamic_reconfigure/server.h>#include <pses_simulation/RangeSensorConfig.h>
Go to the source code of this file.
Classes | |
| struct | YAML::convert< geometry_msgs::Pose > |
| Functor to decode/encode a YAML::Node. More... | |
Namespaces | |
| usscan | |
| This namespace groups all typedefs, utility functions and parameter getter used in the simulation_us node. | |
| YAML | |
| This namespace contains special functionality to parse from .yaml files or write to .yaml files. | |
Typedefs | |
| typedef std::shared_ptr< geometry_msgs::Pose > | usscan::pose_msg_ptr |
| shortcut for a pointer to a pose message More... | |
| typedef std::shared_ptr< sensor_msgs::Range > | usscan::scan_msg_ptr |
| shortcut for a pointer to a range message More... | |
Functions | |
| 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. More... | |
| void | usscan::fetchLoopRate (ros::NodeHandle *nh, double &loopRate) |
| Get loop rate launch parameter. More... | |
| void | usscan::fetchMapFrameID (ros::NodeHandle *nh, std::string &mapFrameID) |
| Get map frame id launch parameter. More... | |
| void | usscan::fetchMapLocation (ros::NodeHandle *nh, std::string &mapLocation) |
| Get map location launch parameter. More... | |
| void | usscan::fetchMapMetadataLocation (ros::NodeHandle *nh, std::string &mapMetadataLocation) |
| Get map meta data location launch parameter. More... | |
| void | usscan::fetchUSFFrameID (ros::NodeHandle *nh, std::string &usfFrameID) |
| Get front ultra sonic sensor frame id launch parameter. More... | |
| void | usscan::fetchUSFTopic (ros::NodeHandle *nh, std::string &usfTopic) |
| Get front ultra sonic sensor topic launch parameter. More... | |
| void | usscan::fetchUSLFrameID (ros::NodeHandle *nh, std::string &uslFrameID) |
| Get left ultra sonic sensor frame id launch parameter. More... | |
| void | usscan::fetchUSLTopic (ros::NodeHandle *nh, std::string &uslTopic) |
| Get left ultra sonic sensor topic launch parameter. More... | |
| void | usscan::fetchUSRFrameID (ros::NodeHandle *nh, std::string &usrFrameID) |
| Get right ultra sonic sensor frame id launch parameter. More... | |
| void | usscan::fetchUSRTopic (ros::NodeHandle *nh, std::string &usrTopic) |
| Get right ultra sonic sensor topic launch parameter. More... | |
| 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. More... | |
| int | main (int argc, char **argv) |
| Main function of this ros node. More... | |
| cv::Point | usscan::setGridPosition (geometry_msgs::Pose &sensor, nav_msgs::MapMetaData &mapInfo) |
| Calculate the occupancy grid postion of a given pose. More... | |
Variables | |
| static const double | usscan::DEFAULT_LOOP_RATE = 30.0 |
| static const std::string | usscan::DEFAULT_MAP_FRAME_ID = "map" |
| static const std::string | usscan::DEFAULT_MAP_LOCATION |
| static const std::string | usscan::DEFAULT_MAP_METADATA_LOCATION |
| static const std::string | usscan::DEFAULT_US_FRONT_FRAME_ID = "front_sensor" |
| static const std::string | usscan::DEFAULT_US_FRONT_TOPIC = "/uc_bridge/usf" |
| static const std::string | usscan::DEFAULT_US_LEFT_FRAME_ID = "left_sensor" |
| static const std::string | usscan::DEFAULT_US_LEFT_TOPIC = "/uc_bridge/usl" |
| static const std::string | usscan::DEFAULT_US_RIGHT_FRAME_ID = "right_sensor" |
| static const std::string | usscan::DEFAULT_US_RIGHT_TOPIC = "/uc_bridge/usr" |
Implementation simulation_us ros node.
Definition in file simulation_us.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Main function of this ros node.
Definition at line 358 of file simulation_us.cpp.