#include <rfid_reader.h>

Public Member Functions | |
| void | receiveRfids (const stdr_msgs::RfidTagVector &msg) |
| Receives the existent rfid tags. More... | |
| RfidReader (const nav_msgs::OccupancyGrid &map, const stdr_msgs::RfidSensorMsg &msg, const std::string &name, ros::NodeHandle &n) | |
| Default constructor. More... | |
| virtual void | updateSensorCallback () |
| Updates the sensor measurements. More... | |
| ~RfidReader (void) | |
| Default destructor. More... | |
Public Member Functions inherited from stdr_robot::Sensor | |
| std::string | getFrameId (void) const |
| Getter function for returning the sensor frame id. More... | |
| geometry_msgs::Pose2D | getSensorPose (void) const |
| Getter function for returning the sensor pose relatively to robot. More... | |
| virtual | ~Sensor (void) |
| Default destructor. More... | |
Private Attributes | |
| stdr_msgs::RfidSensorMsg | _description |
| < Sonar rfid reader description More... | |
| stdr_msgs::RfidTagVector | rfid_tags_ |
| ros::Subscriber | rfids_subscriber_ |
| The currently existent RFID tags. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from stdr_robot::Sensor | |
| void | checkAndUpdateSensor (const ros::TimerEvent &ev) |
| Checks if transform is available and calls updateSensorCallback() More... | |
| Sensor (const nav_msgs::OccupancyGrid &map, const std::string &name, ros::NodeHandle &n, const geometry_msgs::Pose2D &sensorPose, const std::string &sensorFrameId, float updateFrequency) | |
| Default constructor. More... | |
| void | updateTransform (const ros::TimerEvent &ev) |
| Function for updating the sensor tf transform. More... | |
Protected Attributes inherited from stdr_robot::Sensor | |
| bool | _gotTransform |
| const nav_msgs::OccupancyGrid & | _map |
| Sensor pose relative to robot. More... | |
| const std::string & | _namespace |
| < The base for the sensor frame_id More... | |
| ros::Publisher | _publisher |
| ROS tf listener. More... | |
| const std::string | _sensorFrameId |
| A ROS timer for updating the sensor values. More... | |
| const geometry_msgs::Pose2D | _sensorPose |
| Update frequency of _timer. More... | |
| tf::StampedTransform | _sensorTransform |
| True if sensor got the _sensorTransform. More... | |
| tf::TransformListener | _tfListener |
| ROS transform from sensor to map. More... | |
| ros::Timer | _tfTimer |
| ROS publisher for posting the sensor measurements. More... | |
| ros::Timer | _timer |
| A ROS timer for updating the sensor tf. More... | |
| const float | _updateFrequency |
| Sensor frame id. More... | |
Definition at line 41 of file rfid_reader.h.
| stdr_robot::RfidReader::RfidReader | ( | const nav_msgs::OccupancyGrid & | map, |
| const stdr_msgs::RfidSensorMsg & | msg, | ||
| const std::string & | name, | ||
| ros::NodeHandle & | n | ||
| ) |
Default constructor.
| map | [const nav_msgs::OccupancyGrid&] An occupancy grid map |
| msg | [const stdr_msgs::RfidSensorMsg&] The rfid reader \ description message |
| name | [const std::string&] The sensor frame id without the base |
| n | [ros::NodeHandle&] The ROS node handle |
| map | [const nav_msgs::OccupancyGrid&] An occupancy grid map |
| msg | [const stdr_msgs::SonarSensorMsg&] The sonar description message |
| name | [const std::string&] The sensor frame id without the base |
| n | [ros::NodeHandle&] The ROS node handle |
Definition at line 34 of file rfid_reader.cpp.
| stdr_robot::RfidReader::~RfidReader | ( | void | ) |
| void stdr_robot::RfidReader::receiveRfids | ( | const stdr_msgs::RfidTagVector & | msg | ) |
Receives the existent rfid tags.
| msg | [const stdr_msgs::RfidTagVector&] The rfid tags message |
Definition at line 117 of file rfid_reader.cpp.
|
virtual |
Updates the sensor measurements.
< Must implement the functionality
< Check for max distance
< Needs to change into a realistic measurement
Implements stdr_robot::Sensor.
Definition at line 66 of file rfid_reader.cpp.
|
private |
< Sonar rfid reader description
ROS subscriber for rfids
Definition at line 80 of file rfid_reader.h.
|
private |
Definition at line 86 of file rfid_reader.h.
|
private |
The currently existent RFID tags.
Definition at line 83 of file rfid_reader.h.