Flatland
Public Member Functions | Public Attributes | List of all members
flatland_plugins::Laser Class Reference

#include <laser.h>

Inheritance diagram for flatland_plugins::Laser:
Inheritance graph
[legend]
Collaboration diagram for flatland_plugins::Laser:
Collaboration graph
[legend]

Public Member Functions

float ReportFixture (b2Fixture *fixture, const b2Vec2 &point, const b2Vec2 &normal, float fraction) override
 Box2D raytrace call back method required for implementing the b2RayCastCallback abstract class. More...
 
void OnInitialize (const YAML::Node &config) override
 Initialization for the plugin. More...
 
void BeforePhysicsStep (const Timekeeper &timekeeper) override
 Called when just before physics update. More...
 
void ComputeLaserRanges ()
 Method that contains all of the laser range calculations.
 
void ParseParameters (const YAML::Node &config)
 helper function to extract the paramters from the YAML Node More...
 
- Public Member Functions inherited from flatland_server::ModelPlugin
ModelGetModel ()
 Get model.
 
void Initialize (const std::string &type, const std::string &name, Model *model, const YAML::Node &config)
 The method to initialize the ModelPlugin, required since Pluginlib require the class to have a default constructor. More...
 
bool FilterContact (b2Contact *contact, Entity *&entity, b2Fixture *&this_fixture, b2Fixture *&other_fixture)
 Helper function check if this model is part of the contact, and extracts all the useful information. More...
 
bool FilterContact (b2Contact *contact)
 Helper function check if this model is part of the contact. More...
 
- Public Member Functions inherited from flatland_server::FlatlandPlugin
const PluginType Type ()
 
const std::string & GetName () const
 Get plugin name.
 
const std::string & GetType () const
 Get type of plugin.
 
virtual void AfterPhysicsStep (const Timekeeper &timekeeper)
 This method is called after the Box2D physics step. More...
 
virtual void BeginContact (b2Contact *contact)
 A method that is called for all Box2D begin contacts. More...
 
virtual void EndContact (b2Contact *contact)
 A method that is called for all Box2D end contacts. More...
 
virtual void PreSolve (b2Contact *contact, const b2Manifold *oldManifold)
 A method that is called for Box2D presolve. More...
 
virtual void PostSolve (b2Contact *contact, const b2ContactImpulse *impulse)
 A method that is called for Box2D postsolve. More...
 
virtual ~FlatlandPlugin ()=default
 Flatland plugin destructor.
 

Public Attributes

std::string topic_
 topic name to publish the laser scan
 
Bodybody_
 body the laser frame attaches to
 
Pose origin_
 laser frame w.r.t the body
 
double range_
 laser max range
 
double noise_std_dev_
 noise std deviation
 
double max_angle_
 
double min_angle_
 < laser max angle More...
 
double increment_
 laser angle increment
 
double update_rate_
 the rate laser scan will be published
 
std::string frame_id_
 laser frame id name
 
bool broadcast_tf_
 whether to broadcast laser origin w.r.t body
 
uint16_t layers_bits_
 for setting the layers where laser will function
 
uint16_t reflectance_layers_bits_
 
std::default_random_engine rng_
 random generator
 
std::normal_distribution< double > noise_gen_
 gaussian noise generator
 
Eigen::Matrix3f m_body_to_laser_
 tf from body to laser
 
Eigen::Matrix3f m_world_to_body_
 tf from world to body
 
Eigen::Matrix3f m_world_to_laser_
 tf from world to laser
 
Eigen::MatrixXf m_laser_points_
 laser points in the laser' frame
 
Eigen::MatrixXf m_world_laser_points_
 
Eigen::Vector3f v_zero_point_
 laser point in the world frame More...
 
Eigen::Vector3f v_world_laser_origin_
 (0,0) in the laser frame
 
sensor_msgs::LaserScan laser_scan_
 for publishing laser scan
 
bool did_hit_
 Box2D ray trace checking if ray hits anything.
 
float fraction_
 Box2D ray trace fraction.
 
float intensity_
 Intensity of raytrace collision.
 
ros::Publisher scan_publisher_
 ros laser topic publisher
 
tf::TransformBroadcaster tf_broadcaster_
 broadcast laser frame
 
geometry_msgs::TransformStamped laser_tf_
 tf from body to laser frame
 
UpdateTimer update_timer_
 for controlling update rate
 
- Public Attributes inherited from flatland_server::ModelPlugin
ros::NodeHandle nh_
 ROS node handle.
 
- Public Attributes inherited from flatland_server::FlatlandPlugin
std::string type_
 type of the plugin
 
std::string name_
 name of the plugin
 
ros::NodeHandle nh_
 
PluginType plugin_type_
 

Additional Inherited Members

- Public Types inherited from flatland_server::FlatlandPlugin
enum  PluginType { Invalid, Model, World }
 
- Protected Member Functions inherited from flatland_server::ModelPlugin
 ModelPlugin ()=default
 Model plugin default constructor.
 

Detailed Description

This class implements the model plugin class and provides laser data for the given configurations

Member Function Documentation

void flatland_plugins::Laser::BeforePhysicsStep ( const Timekeeper timekeeper)
overridevirtual

Called when just before physics update.

Parameters
[in]timekeeperObject managing the simulation time

Reimplemented from flatland_server::FlatlandPlugin.

void flatland_plugins::Laser::OnInitialize ( const YAML::Node &  config)
overridevirtual

Initialization for the plugin.

Parameters
[in]configPlugin YAML Node

Implements flatland_server::FlatlandPlugin.

void flatland_plugins::Laser::ParseParameters ( const YAML::Node &  config)

helper function to extract the paramters from the YAML Node

Parameters
[in]configPlugin YAML Node
float flatland_plugins::Laser::ReportFixture ( b2Fixture *  fixture,
const b2Vec2 &  point,
const b2Vec2 &  normal,
float  fraction 
)
override

Box2D raytrace call back method required for implementing the b2RayCastCallback abstract class.

Parameters
[in]fixtureFixture the ray hits
[in]pointPoint the ray hits the fixture
[in]normalVector indicating the normal at the point hit
[in]fractionFraction of ray length at hit point

Member Data Documentation

double flatland_plugins::Laser::min_angle_

< laser max angle

laser min angle

Eigen::Vector3f flatland_plugins::Laser::v_zero_point_

laser point in the world frame

point representing (0,0)


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