Classes | Public Types | Public Member Functions | Protected Slots | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
mapviz_plugins::LaserScanPlugin Class Reference

#include <laserscan_plugin.h>

Inheritance diagram for mapviz_plugins::LaserScanPlugin:
Inheritance graph
[legend]

Classes

struct  Scan
 
struct  StampedPoint
 

Public Types

enum  {
  COLOR_FLAT = 0, COLOR_INTENSITY = 1, COLOR_RANGE = 2, COLOR_X = 3,
  COLOR_Y = 4, COLOR_Z = 5
}
 

Public Member Functions

void ClearHistory ()
 
void Draw (double x, double y, double scale)
 
QWidget * GetConfigWidget (QWidget *parent)
 
bool Initialize (QGLWidget *canvas)
 
 LaserScanPlugin ()
 
void LoadConfig (const YAML::Node &node, const std::string &path)
 
void SaveConfig (YAML::Emitter &emitter, const std::string &path)
 
void Shutdown ()
 
void Transform ()
 
virtual ~LaserScanPlugin ()
 
- Public Member Functions inherited from mapviz::MapvizPlugin
int DrawOrder () const
 
void DrawPlugin (double x, double y, double scale)
 
bool GetTransform (const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
 
bool GetTransform (const std::string &source, const ros::Time &stamp, swri_transform_util::Transform &transform)
 
virtual bool Initialize (boost::shared_ptr< tf::TransformListener > tf_listener, swri_transform_util::TransformManagerPtr tf_manager, QGLWidget *canvas)
 
std::string Name () const
 
virtual void Paint (QPainter *painter, double x, double y, double scale)
 
void PaintPlugin (QPainter *painter, double x, double y, double scale)
 
void PrintMeasurements ()
 
void SetDrawOrder (int order)
 
void SetIcon (IconWidget *icon)
 
void SetName (const std::string &name)
 
virtual void SetNode (const ros::NodeHandle &node)
 
void SetTargetFrame (std::string frame_id)
 
void SetType (const std::string &type)
 
void SetUseLatestTransforms (bool value)
 
void SetVisible (bool visible)
 
std::string Type () const
 
bool Visible () const
 
virtual ~MapvizPlugin ()
 

Protected Slots

void AlphaEdited (double val)
 
void BufferSizeChanged (int value)
 
void ColorTransformerChanged (int index)
 
void DrawIcon ()
 
void MaxValueChanged (double value)
 
void MinValueChanged (double value)
 
void PointSizeChanged (int value)
 
void ResetTransformedScans ()
 
void SelectTopic ()
 
void TopicEdited ()
 
void UpdateColors ()
 
void UseRainbowChanged (int check_state)
 

Protected Member Functions

void PrintError (const std::string &message)
 
void PrintInfo (const std::string &message)
 
void PrintWarning (const std::string &message)
 
- Protected Member Functions inherited from mapviz::MapvizPlugin
 MapvizPlugin ()
 

Private Member Functions

QColor CalculateColor (const StampedPoint &point, bool has_intensity)
 
bool GetScanTransform (const Scan &scan, swri_transform_util::Transform &transform)
 
void laserScanCallback (const sensor_msgs::LaserScanConstPtr &scan)
 
void updatePreComputedTriginometic (const sensor_msgs::LaserScanConstPtr &msg)
 

Private Attributes

double alpha_
 
size_t buffer_size_
 
QWidget * config_widget_
 
bool has_message_
 
ros::Subscriber laserscan_sub_
 
double max_value_
 
double min_value_
 
size_t point_size_
 
std::vector< double > precomputed_cos_
 
std::vector< double > precomputed_sin_
 
float prev_angle_min_
 
float prev_increment_
 
size_t prev_ranges_size_
 
std::deque< Scanscans_
 
std::string topic_
 
Ui::laserscan_config ui_
 

Additional Inherited Members

- Public Slots inherited from mapviz::MapvizPlugin
virtual void DrawIcon ()
 
virtual bool SupportsPainting ()
 
- Signals inherited from mapviz::MapvizPlugin
void DrawOrderChanged (int draw_order)
 
void SizeChanged ()
 
void TargetFrameChanged (const std::string &target_frame)
 
void UseLatestTransformsChanged (bool use_latest_transforms)
 
void VisibleChanged (bool visible)
 
- Static Public Member Functions inherited from mapviz::MapvizPlugin
static void PrintErrorHelper (QLabel *status_label, const std::string &message, double throttle=0.0)
 
static void PrintInfoHelper (QLabel *status_label, const std::string &message, double throttle=0.0)
 
static void PrintWarningHelper (QLabel *status_label, const std::string &message, double throttle=0.0)
 
- Protected Attributes inherited from mapviz::MapvizPlugin
QGLWidget * canvas_
 
int draw_order_
 
IconWidgeticon_
 
bool initialized_
 
std::string name_
 
ros::NodeHandle node_
 
std::string source_frame_
 
std::string target_frame_
 
boost::shared_ptr< tf::TransformListenertf_
 
swri_transform_util::TransformManagerPtr tf_manager_
 
std::string type_
 
bool use_latest_transforms_
 
bool visible_
 

Detailed Description

Definition at line 52 of file laserscan_plugin.h.

Member Enumeration Documentation

anonymous enum
Enumerator
COLOR_FLAT 
COLOR_INTENSITY 
COLOR_RANGE 
COLOR_X 
COLOR_Y 
COLOR_Z 

Definition at line 57 of file laserscan_plugin.h.

Constructor & Destructor Documentation

mapviz_plugins::LaserScanPlugin::LaserScanPlugin ( )

Definition at line 62 of file laserscan_plugin.cpp.

mapviz_plugins::LaserScanPlugin::~LaserScanPlugin ( )
virtual

Definition at line 158 of file laserscan_plugin.cpp.

Member Function Documentation

void mapviz_plugins::LaserScanPlugin::AlphaEdited ( double  val)
protectedslot

Coerces alpha to [0.0, 1.0] and stores it in alpha_

Definition at line 679 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::BufferSizeChanged ( int  value)
protectedslot

Definition at line 323 of file laserscan_plugin.cpp.

QColor mapviz_plugins::LaserScanPlugin::CalculateColor ( const StampedPoint point,
bool  has_intensity 
)
private

Definition at line 210 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::ClearHistory ( )
virtual

Reimplemented from mapviz::MapvizPlugin.

Definition at line 162 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::ColorTransformerChanged ( int  index)
protectedslot

Definition at line 640 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::Draw ( double  x,
double  y,
double  scale 
)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 471 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::DrawIcon ( )
protectedslot

Definition at line 168 of file laserscan_plugin.cpp.

QWidget * mapviz_plugins::LaserScanPlugin::GetConfigWidget ( QWidget *  parent)
virtual

Reimplemented from mapviz::MapvizPlugin.

Definition at line 455 of file laserscan_plugin.cpp.

bool mapviz_plugins::LaserScanPlugin::GetScanTransform ( const Scan scan,
swri_transform_util::Transform transform 
)
private

Definition at line 363 of file laserscan_plugin.cpp.

bool mapviz_plugins::LaserScanPlugin::Initialize ( QGLWidget *  canvas)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 462 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::laserScanCallback ( const sensor_msgs::LaserScanConstPtr &  scan)
private

Definition at line 380 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::LoadConfig ( const YAML::Node &  node,
const std::string &  path 
)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 554 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::MaxValueChanged ( double  value)
protectedslot

Definition at line 317 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::MinValueChanged ( double  value)
protectedslot

Definition at line 311 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::PointSizeChanged ( int  value)
protectedslot

Definition at line 336 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::PrintError ( const std::string &  message)
protectedvirtual

Implements mapviz::MapvizPlugin.

Definition at line 440 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::PrintInfo ( const std::string &  message)
protectedvirtual

Implements mapviz::MapvizPlugin.

Definition at line 445 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::PrintWarning ( const std::string &  message)
protectedvirtual

Implements mapviz::MapvizPlugin.

Definition at line 450 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::ResetTransformedScans ( )
protectedslot

Definition at line 202 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::SaveConfig ( YAML::Emitter &  emitter,
const std::string &  path 
)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 684 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::SelectTopic ( )
protectedslot

Definition at line 274 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::Shutdown ( )
inlinevirtual

Implements mapviz::MapvizPlugin.

Definition at line 70 of file laserscan_plugin.h.

void mapviz_plugins::LaserScanPlugin::TopicEdited ( )
protectedslot

Definition at line 286 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::Transform ( )
virtual

Implements mapviz::MapvizPlugin.

Definition at line 521 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::UpdateColors ( )
protectedslot

Definition at line 261 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::updatePreComputedTriginometic ( const sensor_msgs::LaserScanConstPtr &  msg)
private

Definition at line 341 of file laserscan_plugin.cpp.

void mapviz_plugins::LaserScanPlugin::UseRainbowChanged ( int  check_state)
protectedslot

Definition at line 502 of file laserscan_plugin.cpp.

Member Data Documentation

double mapviz_plugins::LaserScanPlugin::alpha_
private

Definition at line 132 of file laserscan_plugin.h.

size_t mapviz_plugins::LaserScanPlugin::buffer_size_
private

Definition at line 136 of file laserscan_plugin.h.

QWidget* mapviz_plugins::LaserScanPlugin::config_widget_
private

Definition at line 129 of file laserscan_plugin.h.

bool mapviz_plugins::LaserScanPlugin::has_message_
private

Definition at line 138 of file laserscan_plugin.h.

ros::Subscriber mapviz_plugins::LaserScanPlugin::laserscan_sub_
private

Definition at line 144 of file laserscan_plugin.h.

double mapviz_plugins::LaserScanPlugin::max_value_
private

Definition at line 134 of file laserscan_plugin.h.

double mapviz_plugins::LaserScanPlugin::min_value_
private

Definition at line 133 of file laserscan_plugin.h.

size_t mapviz_plugins::LaserScanPlugin::point_size_
private

Definition at line 135 of file laserscan_plugin.h.

std::vector<double> mapviz_plugins::LaserScanPlugin::precomputed_cos_
private

Definition at line 145 of file laserscan_plugin.h.

std::vector<double> mapviz_plugins::LaserScanPlugin::precomputed_sin_
private

Definition at line 146 of file laserscan_plugin.h.

float mapviz_plugins::LaserScanPlugin::prev_angle_min_
private

Definition at line 148 of file laserscan_plugin.h.

float mapviz_plugins::LaserScanPlugin::prev_increment_
private

Definition at line 149 of file laserscan_plugin.h.

size_t mapviz_plugins::LaserScanPlugin::prev_ranges_size_
private

Definition at line 147 of file laserscan_plugin.h.

std::deque<Scan> mapviz_plugins::LaserScanPlugin::scans_
private

Definition at line 143 of file laserscan_plugin.h.

std::string mapviz_plugins::LaserScanPlugin::topic_
private

Definition at line 131 of file laserscan_plugin.h.

Ui::laserscan_config mapviz_plugins::LaserScanPlugin::ui_
private

Definition at line 128 of file laserscan_plugin.h.


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


mapviz_plugins
Author(s): Marc Alban
autogenerated on Fri Mar 19 2021 02:44:32