Parasol Planning Library (PPL)
Actuator Class Referencefinal

#include <Actuator.h>

Public Types

Local Types
enum class  DynamicsType { Force , Velocity }
 

Public Member Functions

Construction
 Actuator (Robot *const _r, const std::string &_label, const DynamicsType _t=DynamicsType::Force)
 
 Actuator (Robot *const _r, XMLNode &_node)
 
 Actuator (Robot *const _r, const Actuator &_a)
 
Properties
RobotGetRobot () const
 Get the robot that the actuator is on. More...
 
std::string GetLabel () const
 Get the label for this actuator. More...
 
DynamicsType GetDynamicsType () const
 Get the type of output this actuator produces. More...
 
void SetLimits (const std::vector< double > &_min, const std::vector< double > &_max)
 
void SetMaxForce (const double _total)
 
Planning Interface
std::vector< bool > ControlMask () const
 
std::vector< double > ComputeOutput (const Control::Signal &_s) const
 
Control::Signal ComputeNearestSignal (const std::vector< double > &_force) const
 
Control GetRandomControl () const noexcept
 Get a random control in this actuator's control space. More...
 

Friends

Debug
std::ostream & operator<< (std::ostream &, const Actuator &)
 Print an actuator's state to an ostream. More...
 

Detailed Description

Models an actuator on a robot, such as an engine or motor.

Actuators model a means of locomotion for a robot. They accept a control signal and produce a generalized force on one or more of the robot's DOFs. There are limits on the maximum forward/backward force that can be applied to each DOF, and an additional limit on the maximum total force.

The range of all possible controls that an actuator can accept is represented with a ControlSpace.

The actuator is also able to apply a control to the simulated robot with the Execute method.

Warning
The max force doesn't distinguish between forces and torques: it is a maximum generalized force. It's unlikely that this object will make much sense if it controls both force DOFs (i.e., translation or prismatic joint extension) and torque DOFs (i.e., rotation and revolute/spherical joints).

Member Enumeration Documentation

◆ DynamicsType

The types of dynamics supported. Force-based actuators exert forces on a robot, while velocity-based actuators simply set the velocity.

Enumerator
Force 
Velocity 

Constructor & Destructor Documentation

◆ Actuator() [1/3]

Actuator::Actuator ( Robot *const  _r,
const std::string &  _label,
const DynamicsType  _t = DynamicsType::Force 
)

Construct an empty actuator for a given robot.

Parameters
_rThe owning robot.
_labelThe actuator label.
_tThe dynamics type.

◆ Actuator() [2/3]

Actuator::Actuator ( Robot *const  _r,
XMLNode _node 
)

Construct an actuator for a given robot from an XML input.

Parameters
_rThe owning robot.
_nodeThe XML input node.

◆ Actuator() [3/3]

Actuator::Actuator ( Robot *const  _r,
const Actuator _a 
)

Copy an actuator to another robot.

Parameters
_rThe robot which will own the new copy.
_aThe actuator to copy.

Member Function Documentation

◆ ComputeNearestSignal()

Control::Signal Actuator::ComputeNearestSignal ( const std::vector< double > &  _force) const

Compute the best-match signal to get this actuator to produce a given force.

Parameters
_forceThe desired force in the robot's local frame.
Returns
The signal in this actuator's control space that produces the effect most similar to _force.

◆ ComputeOutput()

std::vector< double > Actuator::ComputeOutput ( const Control::Signal _s) const

Compute the output (force or velocity) generated by driving the actuator at some fraction of its total power.

Parameters
_sThe control signal to apply.
Returns
The force/velocity generated in the robot's local frame by driving this with control signal _s.
Todo:
Generalize this so that the robot's starting point can be taken into account. Currently we assume that the generated force is independent of starting state.

◆ ControlMask()

std::vector< bool > Actuator::ControlMask ( ) const

Get the control mask for this actuator, which indicates the DOFs that it can affect.

Returns
A vector with one boolean for each DOF, where true indicates that the actuator can affect that DOF.

◆ GetDynamicsType()

Actuator::DynamicsType Actuator::GetDynamicsType ( ) const

Get the type of output this actuator produces.

◆ GetLabel()

std::string Actuator::GetLabel ( ) const

Get the label for this actuator.

◆ GetRandomControl()

Control Actuator::GetRandomControl ( ) const
noexcept

Get a random control in this actuator's control space.

◆ GetRobot()

Robot * Actuator::GetRobot ( ) const

Get the robot that the actuator is on.

◆ SetLimits()

void Actuator::SetLimits ( const std::vector< double > &  _min,
const std::vector< double > &  _max 
)

Set the minimum and maximum generalized forces that this actuator can apply to any DOF.

Parameters
_minThe minimum generalized forces.
_maxThe maximum generalized forces.

◆ SetMaxForce()

void Actuator::SetMaxForce ( const double  _total)

Set the maximum total generalized force that this actuator can apply.

Parameters
_totalThe greatest total generalized force that can be applied.

Friends And Related Function Documentation

◆ operator<<

std::ostream& operator<< ( std::ostream &  _os,
const Actuator _a 
)
friend

Print an actuator's state to an ostream.


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