gazebo::CPCROSPlugin
Inherits from gazebo::ROSBaseModelPlugin, gazebo::ROSBasePlugin, ModelPlugin
Public Functions
| Name | |
|---|---|
| CPCROSPlugin() Class constructor. |
|
| virtual | ~CPCROSPlugin() Class destructor. |
| virtual void | Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) Load the plugin. |
Protected Functions
| Name | |
|---|---|
| virtual bool | OnUpdate(const common::UpdateInfo & _info) Update sensor measurement. |
| virtual void | OnPlumeParticlesUpdate(const sensor_msgs::PointCloud::ConstPtr & _msg) Update callback from simulator. |
Protected Attributes
| Name | |
|---|---|
| ros::Subscriber | particlesSub Input topic for the plume particle point cloud. |
| ros::Publisher | salinityPub Output topic for salinity measurements based on the particle concentration. |
| bool | updatingCloud Flag to ensure the cloud and measurement update don't coincide. |
| double | gamma Gamma velocity parameter for the smoothing function. |
| double | gain Sensor gain. |
| double | smoothingLength |
| ros::Time | lastUpdateTimestamp Last update from the point cloud callback. |
| uuv_sensor_ros_plugins_msgs::ChemicalParticleConcentration | outputMsg Output measurement topic. |
| uuv_sensor_ros_plugins_msgs::Salinity | salinityMsg Output salinity measurement message. |
| double | waterSalinityValue |
| double | plumeSalinityValue |
Additional inherited members
Public Functions inherited from gazebo::ROSBaseModelPlugin
| Name | |
|---|---|
| ROSBaseModelPlugin() Class constructor. |
|
| virtual | ~ROSBaseModelPlugin() Class destructor. |
Protected Functions inherited from gazebo::ROSBaseModelPlugin
| Name | |
|---|---|
| void | SendLocalNEDTransform() Returns true if the base_link_ned frame exists. |
Protected Attributes inherited from gazebo::ROSBaseModelPlugin
| Name | |
|---|---|
| physics::ModelPtr | model Pointer to the model. |
| physics::LinkPtr | link Pointer to the link. |
| bool | enableLocalNEDFrame True if a the local NED frame needs to be broadcasted. |
| tf::TransformBroadcaster * | tfBroadcaster TF broadcaster for the local NED frame. |
| ignition::math::Pose3d | localNEDFrame Pose of the local NED frame wrt link frame. |
| tf::StampedTransform | tfLocalNEDFrame Local NED TF frame. |
Public Functions inherited from gazebo::ROSBasePlugin
| Name | |
|---|---|
| ROSBasePlugin() Class constructor. |
|
| virtual | ~ROSBasePlugin() Class destructor. |
| bool | InitBasePlugin(sdf::ElementPtr _sdf) Initialize base plugin. |
| bool | AddNoiseModel(std::string _name, double _sigma) Add noise normal distribution to the list. |
Protected Functions inherited from gazebo::ROSBasePlugin
| Name | |
|---|---|
| bool | IsOn() Returns true if the plugin is activated. |
| void | PublishState() Publish the current state of the plugin. |
| bool | ChangeSensorState(uuv_sensor_ros_plugins_msgs::ChangeSensorState::Request & _req, uuv_sensor_ros_plugins_msgs::ChangeSensorState::Response & _res) Change sensor state (ON/OFF) |
| void | GetTFMessage(const tf::tfMessage::ConstPtr & _msg) Callback function for the static TF message. |
| double | GetGaussianNoise(double _amp) Returns noise value for a function with zero mean from the default Gaussian noise model. |
| double | GetGaussianNoise(std::string _name, double _amp) Returns noise value for a function with zero mean from a Gaussian noise model according to the model name. |
| bool | EnableMeasurement(const common::UpdateInfo & _info) const Enables generation of simulated measurement if the timeout since the last update has been reached. |
| void | UpdateReferenceFramePose() Updates the pose of the reference frame wrt the world frame. |
Protected Attributes inherited from gazebo::ROSBasePlugin
| Name | |
|---|---|
| std::string | robotNamespace Robot namespace. |
| std::string | sensorOutputTopic Name of the sensor's output topic. |
| physics::WorldPtr | world Pointer to the world. |
| event::ConnectionPtr | updateConnection Pointer to the update event connection. |
| common::Time | lastMeasurementTime (Simulation) time when the last sensor measurement was generated. |
| double | updateRate Sensor update rate. |
| double | noiseSigma Noise standard deviation. |
| double | noiseAmp Noise amplitude. |
| bool | gazeboMsgEnabled Flag set to true if the Gazebo sensors messages are supposed to be published as well (it can avoid unnecessary overhead in case) the sensor messages needed are only ROS messages. |
| std::default_random_engine | rndGen Pseudo random number generator. |
| std::map< std::string, std::normal_distribution< double > > | noiseModels Normal distribution describing the noise models. |
| std_msgs::Bool | isOn Flag to control the generation of output messages. |
| boost::shared_ptr< ros::NodeHandle > | rosNode ROS node handle for communication with ROS. |
| transport::NodePtr | gazeboNode Gazebo's node handle for transporting measurement messages. |
| ros::Publisher | rosSensorOutputPub Gazebo's publisher for transporting measurement messages. |
| transport::PublisherPtr | gazeboSensorOutputPub Gazebo's publisher for transporting measurement messages. |
| ros::ServiceServer | changeSensorSrv Service server object. |
| ros::Publisher | pluginStatePub ROS publisher for the switchable sensor data. |
| ignition::math::Pose3d | referenceFrame Pose of the reference frame wrt world frame. |
| ros::Subscriber | tfStaticSub ROS subscriber for the TF static reference frame. |
| std::string | referenceFrameID Frame ID of the reference frame. |
| bool | isReferenceInit Flag set to true if reference frame initialized. |
| physics::LinkPtr | referenceLink Reference link. |
Public Functions Documentation
function CPCROSPlugin
CPCROSPlugin()
Class constructor.
function ~CPCROSPlugin
virtual ~CPCROSPlugin()
Class destructor.
function Load
virtual void Load(
physics::ModelPtr _model,
sdf::ElementPtr _sdf
)
Load the plugin.
Reimplements: gazebo::ROSBaseModelPlugin::Load
Protected Functions Documentation
function OnUpdate
virtual bool OnUpdate(
const common::UpdateInfo & _info
)
Update sensor measurement.
Reimplements: gazebo::ROSBaseModelPlugin::OnUpdate
function OnPlumeParticlesUpdate
virtual void OnPlumeParticlesUpdate(
const sensor_msgs::PointCloud::ConstPtr & _msg
)
Update callback from simulator.
Protected Attributes Documentation
variable particlesSub
ros::Subscriber particlesSub;
Input topic for the plume particle point cloud.
variable salinityPub
ros::Publisher salinityPub;
Output topic for salinity measurements based on the particle concentration.
variable updatingCloud
bool updatingCloud;
Flag to ensure the cloud and measurement update don't coincide.
variable gamma
double gamma;
Gamma velocity parameter for the smoothing function.
variable gain
double gain;
Sensor gain.
variable smoothingLength
double smoothingLength;
variable lastUpdateTimestamp
ros::Time lastUpdateTimestamp;
Last update from the point cloud callback.
variable outputMsg
uuv_sensor_ros_plugins_msgs::ChemicalParticleConcentration outputMsg;
Output measurement topic.
variable salinityMsg
uuv_sensor_ros_plugins_msgs::Salinity salinityMsg;
Output salinity measurement message.
variable waterSalinityValue
double waterSalinityValue;
variable plumeSalinityValue
double plumeSalinityValue;
Updated on 2022-06-01 at 12:37:01 +0000