nAxesGeneratorPos Class Reference
[The Joint Control Components]

This component generates paths between the current positions and new desired positions for multiple axes. More...

#include <nAxesGeneratorPos.hpp>

List of all members.

Public Member Functions

 nAxesGeneratorPos (std::string name)
 Constructor of the class.
virtual bool configureHook ()
 Configures the component, make sure the properties are updated using the OCL::DeploymentComponent or the marshalling interface of the component.
virtual bool startHook ()
 Starts the component.
virtual void updateHook ()
 Updates the desired position and velocity according to the calculated profile.
virtual void stopHook ()

Protected Attributes

RTT::Command< bool(std::vector
< double >, double)> 
moveTo_cmd
 Command that generates a new motion-profile starting from the current time.
RTT::Method< void(void)> reset_position_mtd
 Method that resets the generators desired position to the current measured position and the desired velocity to zero.
RTT::ReadDataPort< std::vector
< double > > 
p_m_port
 DataPort containing the current measured position.
RTT::WriteDataPort
< std::vector< double > > 
p_d_port
 DataPort containing the current desired position.
RTT::WriteDataPort
< std::vector< double > > 
v_d_port
 DataPort containing the current desired velocity.
RTT::Property< std::vector
< double > > 
v_max_prop
 Vector with the maximum velocity of each axis.
RTT::Property< std::vector
< double > > 
a_max_prop
 Vector with the maximum acceleration of each axis.
RTT::Property< unsigned int > num_axes_prop
 Number of axes to configure the component for.

Detailed Description

This component generates paths between the current positions and new desired positions for multiple axes.

It uses KDL for the time interpolation. The paths of all axes are synchronised, this means that all axes movements are scaled in time to the longest axis-movement. The interpolation uses a trapezoidal velocity profile using a maximum acceleration and a maximum velocity.

The initial state of the component is PreOperational.

Definition at line 52 of file nAxesGeneratorPos.hpp.


Constructor & Destructor Documentation

nAxesGeneratorPos ( std::string  name  ) 

Member Function Documentation

bool configureHook (  )  [virtual]

Configures the component, make sure the properties are updated using the OCL::DeploymentComponent or the marshalling interface of the component.

The number of axes, maximum velocities and accelerations for the profiles are updated.

Returns:
false if the velocities and accelerations properties do not match the number of axes, true otherwise

Definition at line 68 of file nAxesGeneratorPos.cpp.

References nAxesGeneratorPos::a_max_prop, nAxesGeneratorPos::num_axes_prop, nAxesGeneratorPos::p_d_port, nAxesGeneratorPos::v_d_port, and nAxesGeneratorPos::v_max_prop.

bool startHook (  )  [virtual]

Starts the component.

Returns:
failes if the input-ports are not ready or the size of the input-ports does not match the number of axes this component is configured for.

Definition at line 109 of file nAxesGeneratorPos.cpp.

References nAxesGeneratorPos::p_d_port, and nAxesGeneratorPos::p_m_port.


Member Data Documentation

RTT::Command<bool(std::vector<double>,double)> moveTo_cmd [protected]

Command that generates a new motion-profile starting from the current time.

The command is completed when the duration is passed.

Parameters:
position a vector with the desired positions of the axes
time the minimum time duration of the movement, if zero the movement will be as fast as possible.
Returns:
false if another motion is still going on or the size of the position parameter does not match the number of axes the component is configured for, true otherwise.

Definition at line 113 of file nAxesGeneratorPos.hpp.

Referenced by nAxesGeneratorPos::nAxesGeneratorPos().


The documentation for this class was generated from the following files:
Generated on Thu Dec 23 15:05:29 2010 for OrocosComponentLibrary by  doxygen 1.6.3