119 float pose_theta = yaw;
123 for(
unsigned int i = 0 ; i <
scan_.ranges.size() ; i++)
125 float real_dist =
scan_.ranges[i];
126 if(real_dist >
msg_.maxRange)
128 real_dist =
msg_.maxRange;
131 else if(real_dist <
msg_.minRange)
133 real_dist =
msg_.minRange;
134 painter.setPen(QColor(100,100,100,
146 pose_x / ocgd + real_dist *
147 cos(pose_theta +
scan_.angle_min + i *
scan_.angle_increment)
150 pose_y / ocgd + real_dist *
151 sin(pose_theta +
scan_.angle_min + i *
scan_.angle_increment)
172 float size = m->width();
173 float climax = size / maxRange * ocgd / 2.1;
175 for(
unsigned int i = 0 ; i <
scan_.ranges.size() ; i++)
177 float real_dist =
scan_.ranges[i];
178 if(real_dist >
msg_.maxRange)
180 real_dist =
msg_.maxRange;
181 painter.setPen(QColor(255,0,0,100));
183 else if(real_dist <
msg_.minRange)
185 real_dist =
msg_.minRange;
186 painter.setPen(QColor(100,100,100,100));
190 painter.setPen(QColor(255,0,0,100));
194 size / 2 + (
msg_.pose.x / ocgd) * climax,
195 size / 2 + (
msg_.pose.y / ocgd) * climax,
197 size / 2 + ((
msg_.pose.x / ocgd) + real_dist *
198 cos(
scan_.angle_min + i *
scan_.angle_increment +
msg_.pose.theta)
200 size / 2 + ((
msg_.pose.y / ocgd) + real_dist *
201 sin(
scan_.angle_min + i *
scan_.angle_increment +
msg_.pose.theta)
214 return msg_.maxRange;
223 return msg_.frame_id;
float getMaxRange(void)
Returns the max range of the specific laser sensor.
char getVisualizationStatus(void)
Returns the visibility status of the specific laser sensor.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setVisualizationStatus(char vs)
Sets the visibility status of the specific laser sensor.
CGuiLaser(stdr_msgs::LaserSensorMsg msg, std::string baseTopic)
Default contructor.
~CGuiLaser(void)
Default destructor.
ros::Subscriber subscriber_
The ros laser scan msg.
char visualization_status_
TFSIMD_FORCE_INLINE const tfScalar & x() const
sensor_msgs::LaserScan scan_
Visualization status of the specific laser.
void callback(const sensor_msgs::LaserScan &msg)
Callback for the ros laser message.
void visualizerPaint(QImage *m, float ocgd, float maxRange)
Paints the laser scan in it's own visualizer.
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string topic_
The ROS tf frame.
stdr_msgs::LaserSensorMsg msg_
Subscriber for the ros laser msg.
void toggleVisualizationStatus(void)
Toggles the visibility status of the specific laser sensor.
The main namespace for STDR GUI.
void paint(QImage *m, float ocgd, tf::TransformListener *listener)
Paints the laser scan in the map image.
std::string getFrameId(void)
Returns the frame id of the specific laser sensor.
bool lock_
< Used to avoid drawing when a new laser message arives
std::string tf_frame_
A laser sensor message : Depscription of a laser sensor.