The event generator class. More...
#include <JointEventSource.hh>
Public Types | |
enum | Range { POSITION, ANGLE, VELOCITY, FORCE, INVALID } |
The type of data range measured. More... | |
Public Member Functions | |
JointEventSource (transport::PublisherPtr _pub, physics::WorldPtr _world) | |
Constructor. More... | |
void | Info () const |
Prints data about the event source to the log (useful for debug) More... | |
virtual void | Init () |
Initialize the event. More... | |
virtual void | Load (const sdf::ElementPtr _sdf) |
Loads the full name of the model and the triggers from the world file. More... | |
void | Update () |
Called every simulation step. More... | |
Public Member Functions inherited from gazebo::EventSource | |
EventSource (transport::PublisherPtr _pub, const std::string &_type, physics::WorldPtr _world) | |
Constructor. More... | |
virtual | ~EventSource () |
Destructor. More... | |
void | Emit (const std::string &_data) const |
emit an event with data to the internal publisher (and using the internal type) More... | |
virtual bool | IsActive () const |
An event source can be used to enable other events. More... | |
Additional Inherited Members | |
Protected Attributes inherited from gazebo::EventSource | |
bool | active |
True if the event source is active. More... | |
std::string | name |
Name of the event. More... | |
transport::PublisherPtr | pub |
a way to send messages to the other topics (to the REST) More... | |
std::string | type |
Type of event. More... | |
physics::WorldPtr | world |
Pointer to the world. More... | |
The event generator class.
Events are generated when joint enters or leaves a certain trigger state. This type of event works with joints that have a single axis (revolute or prismatic). These are the most common for actuated joints. Triggers must be defined in the world, but models can be created during the simulation. Triggers cannot overlap.
/// /// This is an example joint event. It is triggered when the joint named /// "joint" in the model "revoluter" has an angle value that enters or /// leaves the range [3, 3.1416]. Triggers can also depend on the position, /// velocity or applied force. /// /// <event> /// <name>joint_angle</name> /// <type>joint</type> /// <model>revoluter</model> /// <joint>joint</joint> /// <range> /// <type>normalized_angle</type> /// <min>3</min> /// <max>3.1416</max> /// </range> /// </event> /// ///
gazebo::JointEventSource::JointEventSource | ( | transport::PublisherPtr | _pub, |
physics::WorldPtr | _world | ||
) |
Constructor.
[in] | _pub | the publisher for the SimEvents |
[in] | _world | Pointer to the world. |
void gazebo::JointEventSource::Info | ( | ) | const |
Prints data about the event source to the log (useful for debug)
|
virtual |
Initialize the event.
Reimplemented from gazebo::EventSource.
|
virtual |
Loads the full name of the model and the triggers from the world file.
[in] | _sdf | The root sdf element for this joint event |
Reimplemented from gazebo::EventSource.
void gazebo::JointEventSource::Update | ( | ) |
Called every simulation step.