#include <rfid_reader.h>
Public Member Functions | |
void | receiveRfids (const stdr_msgs::RfidTagVector &msg) |
Receives the existent rfid tags. | |
RfidReader (const nav_msgs::OccupancyGrid &map, const stdr_msgs::RfidSensorMsg &msg, const std::string &name, ros::NodeHandle &n) | |
Default constructor. | |
virtual void | updateSensorCallback () |
Updates the sensor measurements. | |
~RfidReader (void) | |
Default destructor. | |
Private Attributes | |
stdr_msgs::RfidSensorMsg | _description |
< Sonar rfid reader description | |
stdr_msgs::RfidTagVector | rfid_tags_ |
ros::Subscriber | rfids_subscriber_ |
The currently existent RFID tags. |
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.
void stdr_robot::RfidReader::updateSensorCallback | ( | void | ) | [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.
stdr_msgs::RfidSensorMsg stdr_robot::RfidReader::_description [private] |
< Sonar rfid reader description
ROS subscriber for rfids
Definition at line 82 of file rfid_reader.h.
stdr_msgs::RfidTagVector stdr_robot::RfidReader::rfid_tags_ [private] |
Definition at line 86 of file rfid_reader.h.
The currently existent RFID tags.
Definition at line 85 of file rfid_reader.h.