Flatland
|
#include <gps.h>
Public Member Functions | |
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 | ParseParameters (const YAML::Node &config) |
Helper function to extract the paramters from the YAML Node. More... | |
void | ComputeReferenceEcef () |
Method to compute ECEF coordinates of reference latitude and longitude, assuming zero altitude. | |
void | UpdateFix () |
Method that updates the current state of the GPS fix output for publishing. | |
Public Member Functions inherited from flatland_server::ModelPlugin | |
Model * | GetModel () |
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 GPS fix | |
std::string | frame_id_ |
GPS frame ID. | |
Body * | body_ |
body the simulated GPS antenna attaches to | |
Pose | origin_ |
GPS sensor frame w.r.t the body. | |
double | ref_lat_rad_ |
double | ref_lon_rad_ |
double | ref_ecef_x_ |
double | ref_ecef_y_ |
double | ref_ecef_z_ |
double | update_rate_ |
GPS fix publish rate. | |
bool | broadcast_tf_ |
whether to broadcast laser origin w.r.t body | |
ros::Publisher | fix_publisher_ |
GPS fix topic publisher. | |
tf::TransformBroadcaster | tf_broadcaster_ |
broadcast GPS frame | |
geometry_msgs::TransformStamped | gps_tf_ |
tf from body to GPS frame | |
sensor_msgs::NavSatFix | gps_fix_ |
message for publishing output | |
UpdateTimer | update_timer_ |
for controlling update rate | |
Eigen::Matrix3f | m_body_to_gps_ |
tf from body to GPS | |
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_ |
Static Public Attributes | |
static double | WGS84_A = 6378137.0 |
Earth's major axis length. | |
static double | WGS84_E2 = 0.0066943799831668 |
Square of Earth's first eccentricity. | |
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. | |
This class simulates a GPS receiver in Flatland
|
overridevirtual |
Called when just before physics update.
[in] | timekeeper | Object managing the simulation time |
Reimplemented from flatland_server::FlatlandPlugin.
|
overridevirtual |
Initialization for the plugin.
[in] | config | Plugin YAML Node |
Implements flatland_server::FlatlandPlugin.
void flatland_plugins::Gps::ParseParameters | ( | const YAML::Node & | config | ) |
Helper function to extract the paramters from the YAML Node.
[in] | config | Plugin YAML Node |
double flatland_plugins::Gps::ref_ecef_x_ |
ECEF coordinates of reference lat and lon at zero altitude
double flatland_plugins::Gps::ref_ecef_y_ |
ECEF coordinates of reference lat and lon at zero altitude
double flatland_plugins::Gps::ref_ecef_z_ |
ECEF coordinates of reference lat and lon at zero altitude
double flatland_plugins::Gps::ref_lat_rad_ |
latitude in radians corresponding to (0, 0) in map frame
double flatland_plugins::Gps::ref_lon_rad_ |
longitude in radians corresponding to (0, 0) in map frame