83 float pose_theta = yaw;
87 painter.setBrush(brush);
89 for(
unsigned int j = 0 ; j <
tags_.rfid_tags_ids.size() ; j++)
91 for(
unsigned int i = 0 ; i <
env_tags_.rfid_tags.size() ; i++)
95 int x1 = pose_x / ocgd;
96 int y1 = pose_y / ocgd;
97 int x2 =
env_tags_.rfid_tags[i].pose.x / ocgd;
98 int y2 =
env_tags_.rfid_tags[i].pose.y / ocgd;
99 painter.drawLine(x1, y1, x2, y2);
106 painter.setBrush(brush_cone);
107 QPen pen(QColor(0,0,0,0));
111 pose_x / ocgd -
msg_.maxRange / ocgd,
113 pose_y / ocgd -
msg_.maxRange / ocgd,
115 msg_.maxRange / ocgd * 2,
116 msg_.maxRange / ocgd * 2,
118 - (pose_theta -
msg_.angleSpan / 2.0)
164 return msg_.frame_id;
void setEnvironmentalTags(stdr_msgs::RfidTagVector env_tags)
Sets the tags existent in the environment.
bool lock_
The ROS tf frame.
std::string tf_frame_
Visualization status of the specific sonar.
void callback(const stdr_msgs::RfidSensorMeasurementMsg &msg)
Callback for the rfid measurement message.
stdr_msgs::RfidSensorMsg msg_
A ros subscriber.
std::string getFrameId(void)
Returns the frame id of the specific sensor.
stdr_msgs::RfidSensorMeasurementMsg tags_
The tags that exist in the environment.
ros::Subscriber subscriber_
Used to avoid drawing when a new sonar message arives.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void toggleVisualizationStatus(void)
Toggles the visibility status of the specific sensor.
void setVisualizationStatus(char vs)
Sets the visibility status of the specific sensor.
stdr_msgs::RfidTagVector env_tags_
CGuiRfid(stdr_msgs::RfidSensorMsg msg, std::string baseTopic)
Default contructor.
TFSIMD_FORCE_INLINE const tfScalar & x() const
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
char visualization_status_
The stdr rfid sensor measurement msg.
TFSIMD_FORCE_INLINE const tfScalar & y() const
The main namespace for STDR GUI.
std::string topic_
< The topic from which the new RFID tags will be got
~CGuiRfid(void)
Default destructor.
char getVisualizationStatus(void)
Returns the visibility status of the specific sensor.
void paint(QImage *m, float ocgd, tf::TransformListener *listener)
Paints the rfid measurements in the map image.