Gazebo Sim

API Reference

9.0.0
TrajectoryFollower Class Reference

A plugin that scripts the movement of a model based on waypoints. Note that at this point, the trajectory is always in 2D (x, y). The plugin applies a torque until the model is aligned with the next waypoint. Then, it applies a force until the model is close enough to the waypoint. More...

#include <TrajectoryFollower.hh>

Public Member Functions

 TrajectoryFollower ()
 Constructor.
 
 ~TrajectoryFollower () override=default
 Destructor.
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override
 Configure the system.
 
bool IsEnabled (Entity _entity, const EntityComponentManager &_ecm) const
 Check if an entity is enabled or not.
 
void PreUpdate (const UpdateInfo &_info, EntityComponentManager &_ecm) override
 
- Public Member Functions inherited from System
 System ()=default
 Constructor.
 
virtual ~System ()=default
 Destructor.
 

Additional Inherited Members

- Public Types inherited from System
using PriorityType = int32_t
 Signed integer type used for specifying priority of the execution order of PreUpdate and Update phases.
 
- Static Public Attributes inherited from System
static constexpr PriorityType kDefaultPriority = {0}
 Default priority value for execution order of the PreUpdate and Update phases.
 
static constexpr std::string_view kPriorityElementName
 Name of the XML element from which the priority value will be parsed.
 

Detailed Description

A plugin that scripts the movement of a model based on waypoints. Note that at this point, the trajectory is always in 2D (x, y). The plugin applies a torque until the model is aligned with the next waypoint. Then, it applies a force until the model is close enough to the waypoint.

This plugin loads a set of waypoints via SDF and traverse the waypoints in sequence. The movement is generated applying force and torque to one of of the model links. It's also possible to loop through the waypoints for generating a never ending trajectory. Waypoints may be inserted manually via the <waypoints> element, or generated relative to the model's initial position via the <line> or <circle> elements. Only one of these options should be used.

System Parameters

This plugin requires the following SDF parameters:

Required parameters:

  • <link_name>: The name of the link within the model where the force/torque will be applied when moving the vehicle.

Optional parameters:

  • <loop>: When true, all waypoints will be visited continously in a circular pattern. If false, the model will stop when the last waypoint is reached. Note, that if the vehicle moves, it will still try to reach the very last waypoint.
  • <waypoints>: Element specifying the set of waypoints that the the model should navigate through. This block should contain at least one of these blocks:
    • <waypoint>: This block should contain the X, Y of a waypoint.
  • <range_tolerance>: The current waypoint is considered reached if the distance to it is within +- this tolerance (m). The default value is 0.5m.
  • <bearing_tolerance>: If the bearing to the current waypoint is within +- this tolerance, a torque won't be applied (degree). The default value is 2 deg.
  • <zero_vel_on_bearing_reached>: Force angular velocity to be zero when target bearing is reached. Default is false. Note: this is an experimental parameter and may be removed in the future.
  • <force>: The force to apply at every plugin iteration in the X direction of the link (N). The default value is 60.
  • <torque>: The torque to apply at every plugin iteration in the Yaw direction of the link (Nm). The default value is 50.
  • <line>: Element that indicates the model should travel in "line" mode. The block should contain the relative direction and distance from the initial position in which the vehicle should move, specified in the world frame.
    • <direction>: Relative direction (radians) in the world frame for the vehicle to travel.
    • <length>: Distance (meters) for the vehicle to travel.
  • <circle>: Element that indicates the model should travel in "circle" mode. The block should contain the desired radius of the circle about the vehicle's initial position
    • <radius>: Radius (meters) of circular path to travel.

Here are three examples:

<plugin
filename="gz-sim-trajectory-follower-system"
name="systems::TrajectoryFollower">
<link_name>base_link</link_name>
<loop>true</loop>
<waypoints>
<waypoint>25 0</waypoint>
<waypoint>15 0</waypoint>
</waypoints>
</plugin>
<plugin
filename="gz-sim-trajectory-follower-system"
name="systems::TrajectoryFollower">
<link_name>base_link</link_name>
<loop>true</loop>
<line>
<direction>0</direction>
<length>5</length>
</line>
</plugin>
<plugin
filename="gz-sim-trajectory-follower-system"
name="systems::TrajectoryFollower">
<link_name>base_link</link_name>
<loop>true</loop>
<circle>
<radius>2</radius>
</circle>
</plugin>

Constructor & Destructor Documentation

◆ TrajectoryFollower()

Constructor.

◆ ~TrajectoryFollower()

~TrajectoryFollower ( )
overridedefault

Destructor.

Member Function Documentation

◆ Configure()

void Configure ( const Entity _entity,
const std::shared_ptr< const sdf::Element > &  _sdf,
EntityComponentManager _ecm,
EventManager _eventMgr 
)
overridevirtual

Configure the system.

Parameters
[in]_entityThe entity this plugin is attached to.
[in]_sdfThe SDF Element associated with this system plugin.
[in]_ecmThe EntityComponentManager of the given simulation instance.
[in]_eventMgrThe EventManager of the given simulation instance.

Implements ISystemConfigure.

◆ IsEnabled()

bool IsEnabled ( Entity  _entity,
const EntityComponentManager _ecm 
) const

Check if an entity is enabled or not.

Parameters
[in]_entityTarget entity
[in]_ecmEntity component manager
Returns
True if buoyancy should be applied.

◆ PreUpdate()

void PreUpdate ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Implements ISystemPreUpdate.


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