Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
toposens_markers::Plot Class Reference

#include <plot.h>

Public Member Functions

 Plot (ros::NodeHandle nh, ros::NodeHandle private_nh)
 
void publishDefaultSensorMesh ()
 
void publishSensorMeshes ()
 
 ~Plot ()
 

Private Types

typedef dynamic_reconfigure::Server< TsMarkersConfig > Cfg
 

Private Member Functions

void _plot (const toposens_msgs::TsScan::ConstPtr &msg)
 
void _reconfig (TsMarkersConfig &cfg, uint32_t level)
 
void _staticTFCallback (const tf2_msgs::TFMessage::ConstPtr &tf)
 

Private Attributes

std::map< std::string, std_msgs::ColorRGBA > _color_map
 
int _color_mode
 
float _color_range
 
std::string _frame_id
 
float _half_color_range
 
double _lifetime
 
std::map< std::string, rviz_visual_tools::colors_mesh_color_map
 
std::map< std::string, geometry_msgs::Pose_pose_map
 
rviz_visual_tools::RvizVisualToolsPtr _rviz
 
std::deque< toposens_msgs::TsScan > _scans
 
ros::Subscriber _scans_sub
 
std::string _sensor_mesh
 
std::shared_ptr< Cfg_srv
 
ros::Subscriber _static_tf_sub
 
std::string _target_frame
 
tf2_ros::Buffer _tf2_buffer
 
tf2_ros::MessageFilter< toposens_msgs::TsScan > * _tf2_filter
 
tf2_ros::TransformListener_tf2_listener
 
message_filters::Subscriber< toposens_msgs::TsScan > _tf2_scans_sub
 

Static Private Attributes

static const auto _baseScale = rviz_visual_tools::scales::LARGE
 

Detailed Description

Handles lifetime management and realtime plotting of TsPoints on Rviz. Visual characteristics of a marker are defined as follows:
Location - 3D coordinates of TsPoint relative to origin, which coincides with the sensor position.
Color - Relative z-distance from the sensor, green being the closest points and red being the farthest.
Scale - Product of the base scale (hard-coded, same for all markers), the user-defined global scale (dynamic, affects all markers equally) and the intensity of an individual TsPoint.

Definition at line 49 of file plot.h.

Member Typedef Documentation

◆ Cfg

typedef dynamic_reconfigure::Server<TsMarkersConfig> toposens_markers::Plot::Cfg
private

Structure generated from cfg file for storing local copy of marker parameters.

Definition at line 74 of file plot.h.

Constructor & Destructor Documentation

◆ Plot()

toposens_markers::Plot::Plot ( ros::NodeHandle  nh,
ros::NodeHandle  private_nh 
)

Subscribes to a TsScans topic and initializes visual tools for rviz plotting.

Parameters
nhPublic nodehandle for pub-sub ops on ROS topics.
private_nhPrivate nodehandle for accessing launch parameters.

A dynamic reconfigure server is set up to change marker scale and lifetime during runtime.

Definition at line 9 of file plot.cpp.

◆ ~Plot()

toposens_markers::Plot::~Plot ( )

Destructor frees memory from heap

Definition at line 47 of file plot.cpp.

Member Function Documentation

◆ _plot()

void toposens_markers::Plot::_plot ( const toposens_msgs::TsScan::ConstPtr &  msg)
private

Converts point coordinates from local sensor coordinates to global coordinates and plots the points.

Parameters
msgPointer to an incoming TsScan message.

Waits for a target frame transform to become available and maps incoming TsPoints to this frame.

Once the transforms are finished, the scene is wiped, old scans are deleted and the remaining scans and sensors are re-plotted.

Definition at line 91 of file plot.cpp.

◆ _reconfig()

void toposens_markers::Plot::_reconfig ( TsMarkersConfig &  cfg,
uint32_t  level 
)
private

Callback triggered when a parameter is altered on the dynamic reconfigure server.

Parameters
cfgStructure holding updated values of parameters on server.
levelIndicates parameter that triggered the callback.

Current implementation defines 2 marker parameters: scale and lifetime. On each trigger, the latest config data structure is copied locally and the user-defined global scale is updated for rviz rendering. No separate updating is done for the lifetime parameter as it is always retrieved directly from the cfg object whenever its value is needed in the code.

Definition at line 60 of file plot.cpp.

◆ _staticTFCallback()

void toposens_markers::Plot::_staticTFCallback ( const tf2_msgs::TFMessage::ConstPtr &  tf)
private

Callback which receives the static transform messages containing the positions of the sensors. These are stored in a dictionary. Unique point colors for each sensor postion are also stored in a dictionary.

Parameters
tfThe transform message.

Adds the sensor transforms to a dictionary so that each time the scene is deleted the sensors can be replaced with their correct poses.

Also Creates a unique color for the points from each sensor.

Definition at line 181 of file plot.cpp.

◆ publishDefaultSensorMesh()

void toposens_markers::Plot::publishDefaultSensorMesh ( )

Plots the default sensor

Definition at line 243 of file plot.cpp.

◆ publishSensorMeshes()

void toposens_markers::Plot::publishSensorMeshes ( )

Plots the sensor graphics

Definition at line 216 of file plot.cpp.

Member Data Documentation

◆ _baseScale

const auto toposens_markers::Plot::_baseScale = rviz_visual_tools::scales::LARGE
staticprivate

Universal scale affecting all markers equally.

Definition at line 52 of file plot.h.

◆ _color_map

std::map<std::string, std_msgs::ColorRGBA> toposens_markers::Plot::_color_map
private

Dictionary of sensor point colors

Definition at line 120 of file plot.h.

◆ _color_mode

int toposens_markers::Plot::_color_mode
private

Maintains current value of marker color mode.

Definition at line 99 of file plot.h.

◆ _color_range

float toposens_markers::Plot::_color_range
private

Maintains current value over which the color is scaled.

Definition at line 100 of file plot.h.

◆ _frame_id

std::string toposens_markers::Plot::_frame_id
private

Frame ID assigned to rviz Marker messages.

Definition at line 97 of file plot.h.

◆ _half_color_range

float toposens_markers::Plot::_half_color_range
private

Maintains current value of the color range offset.

Definition at line 102 of file plot.h.

◆ _lifetime

double toposens_markers::Plot::_lifetime
private

Maintains current value of marker lifetime.

Definition at line 98 of file plot.h.

◆ _mesh_color_map

std::map<std::string, rviz_visual_tools::colors> toposens_markers::Plot::_mesh_color_map
private

Definition at line 121 of file plot.h.

◆ _pose_map

std::map<std::string, geometry_msgs::Pose> toposens_markers::Plot::_pose_map
private

Dictionary of sensor poses

Definition at line 119 of file plot.h.

◆ _rviz

rviz_visual_tools::RvizVisualToolsPtr toposens_markers::Plot::_rviz
private

Helper for plotting markers.

Definition at line 107 of file plot.h.

◆ _scans

std::deque<toposens_msgs::TsScan> toposens_markers::Plot::_scans
private

Data structure for storing incoming scans.

Definition at line 106 of file plot.h.

◆ _scans_sub

ros::Subscriber toposens_markers::Plot::_scans_sub
private

Handler for subscribing to TsScans.

Definition at line 116 of file plot.h.

◆ _sensor_mesh

std::string toposens_markers::Plot::_sensor_mesh
private

File path to the sensor which is to be displayed.

Definition at line 117 of file plot.h.

◆ _srv

std::shared_ptr<Cfg> toposens_markers::Plot::_srv
private

Pointer to config server

Definition at line 104 of file plot.h.

◆ _static_tf_sub

ros::Subscriber toposens_markers::Plot::_static_tf_sub
private

Subscriber to get the positions of the sensors

Definition at line 118 of file plot.h.

◆ _target_frame

std::string toposens_markers::Plot::_target_frame
private

Target frame for scan transformations.

Definition at line 109 of file plot.h.

◆ _tf2_buffer

tf2_ros::Buffer toposens_markers::Plot::_tf2_buffer
private

Stores known frame mapping.

Definition at line 112 of file plot.h.

◆ _tf2_filter

tf2_ros::MessageFilter<toposens_msgs::TsScan>* toposens_markers::Plot::_tf2_filter
private

Reference to the tf2 filter.

Definition at line 114 of file plot.h.

◆ _tf2_listener

tf2_ros::TransformListener* toposens_markers::Plot::_tf2_listener
private

Listener for frame mapping.

Definition at line 113 of file plot.h.

◆ _tf2_scans_sub

message_filters::Subscriber<toposens_msgs::TsScan> toposens_markers::Plot::_tf2_scans_sub
private

Handler for subscribing to TsScans.

Definition at line 111 of file plot.h.


The documentation for this class was generated from the following files:


toposens_markers
Author(s): Adi Singh, Sebastian Dengler, Christopher Lang, Roua Mokchah
autogenerated on Mon Feb 28 2022 23:57:46