Public Member Functions | Private Member Functions | Private Attributes | List of all members
RosReflexxesVelocityInterface Class Reference

#include <RosReflexxesVelocityInterface.h>

Inheritance diagram for RosReflexxesVelocityInterface:
Inheritance graph
[legend]

Public Member Functions

void advance_reflexxes ()
 
std::vector< double > get_current_acceleration () override
 
std::vector< double > get_current_position () override
 
RMLVelocityInputParameters get_current_state ()
 
std::vector< double > get_current_velocity () override
 
double get_period ()
 
std::vector< double > get_target_command () override
 
std::vector< double > get_target_velocity ()
 
bool init (ros::NodeHandle nh) override
 
void reset_to_previous_state (RMLVelocityInputParameters previous_state)
 
 RosReflexxesVelocityInterface ()
 
 RosReflexxesVelocityInterface (ros::NodeHandle nh)
 
 RosReflexxesVelocityInterface (std::string nh)
 
void set_target_command (const std::vector< double > &command) override
 
void set_target_position (const std::vector< double > &t_pos) override
 
void set_target_velocity (const std::vector< double > &t_vel) override
 
void starting (const std::vector< double > &initial_command) override
 
std::vector< double > update () override
 
- Public Member Functions inherited from RosReflexxesInterface
std::vector< double > update (const std::vector< double > &command)
 
virtual ~RosReflexxesInterface ()
 

Private Member Functions

bool load_parameters (std::string ns)
 

Private Attributes

RMLVelocityFlags flags_
 
boost::shared_ptr< RMLVelocityInputParametersinput_params_
 
std::vector< double > max_acceleration_
 
std::vector< double > max_jerk_
 
std::vector< double > max_velocities_
 
int n_dim_
 
ros::NodeHandle nh_
 
boost::shared_ptr< RMLVelocityOutputParametersoutput_params_
 
double period_
 
bool position_initialized_
 
boost::shared_ptr< ReflexxesAPIrml_
 

Detailed Description

Definition at line 12 of file RosReflexxesVelocityInterface.h.

Constructor & Destructor Documentation

RosReflexxesVelocityInterface::RosReflexxesVelocityInterface ( )
inline

Definition at line 32 of file RosReflexxesVelocityInterface.h.

RosReflexxesVelocityInterface::RosReflexxesVelocityInterface ( ros::NodeHandle  nh)
inline

Definition at line 33 of file RosReflexxesVelocityInterface.h.

RosReflexxesVelocityInterface::RosReflexxesVelocityInterface ( std::string  nh)
inline

Definition at line 34 of file RosReflexxesVelocityInterface.h.

Member Function Documentation

void RosReflexxesVelocityInterface::advance_reflexxes ( )

Definition at line 85 of file RosReflexxesVelocityInterface.cpp.

std::vector< double > RosReflexxesVelocityInterface::get_current_acceleration ( )
overridevirtual

Implements RosReflexxesInterface.

Definition at line 108 of file RosReflexxesVelocityInterface.cpp.

std::vector< double > RosReflexxesVelocityInterface::get_current_position ( )
overridevirtual

getter

Implements RosReflexxesInterface.

Definition at line 124 of file RosReflexxesVelocityInterface.cpp.

RMLVelocityInputParameters RosReflexxesVelocityInterface::get_current_state ( )

This getter is given in order to copy and store the current state of reflexxes, in order to be able to reset to a previous state if desired using the stored states retrieved by this function.

Returns
reflexxes input parameters

Definition at line 146 of file RosReflexxesVelocityInterface.cpp.

std::vector< double > RosReflexxesVelocityInterface::get_current_velocity ( )
overridevirtual

Implements RosReflexxesInterface.

Definition at line 116 of file RosReflexxesVelocityInterface.cpp.

double RosReflexxesVelocityInterface::get_period ( )

Definition at line 151 of file RosReflexxesVelocityInterface.cpp.

std::vector<double> RosReflexxesVelocityInterface::get_target_command ( )
inlineoverridevirtual

make ros interface generic

Implements RosReflexxesInterface.

Definition at line 43 of file RosReflexxesVelocityInterface.h.

std::vector< double > RosReflexxesVelocityInterface::get_target_velocity ( )

Definition at line 132 of file RosReflexxesVelocityInterface.cpp.

bool RosReflexxesVelocityInterface::init ( ros::NodeHandle  nh)
overridevirtual

ros methods

Implements RosReflexxesInterface.

Definition at line 4 of file RosReflexxesVelocityInterface.cpp.

bool RosReflexxesVelocityInterface::load_parameters ( std::string  ns)
private

Definition at line 28 of file RosReflexxesVelocityInterface.cpp.

void RosReflexxesVelocityInterface::reset_to_previous_state ( RMLVelocityInputParameters  previous_state)

Definition at line 101 of file RosReflexxesVelocityInterface.cpp.

void RosReflexxesVelocityInterface::set_target_command ( const std::vector< double > &  command)
inlineoverridevirtual

Implements RosReflexxesInterface.

Definition at line 47 of file RosReflexxesVelocityInterface.h.

void RosReflexxesVelocityInterface::set_target_position ( const std::vector< double > &  t_pos)
inlineoverridevirtual

Implements RosReflexxesInterface.

Definition at line 68 of file RosReflexxesVelocityInterface.h.

void RosReflexxesVelocityInterface::set_target_velocity ( const std::vector< double > &  t_vel)
overridevirtual

Implements RosReflexxesInterface.

Definition at line 156 of file RosReflexxesVelocityInterface.cpp.

void RosReflexxesVelocityInterface::starting ( const std::vector< double > &  initial_command)
overridevirtual

Implements RosReflexxesInterface.

Definition at line 72 of file RosReflexxesVelocityInterface.cpp.

std::vector< double > RosReflexxesVelocityInterface::update ( )
overridevirtual

Implements RosReflexxesInterface.

Definition at line 96 of file RosReflexxesVelocityInterface.cpp.

Member Data Documentation

RMLVelocityFlags RosReflexxesVelocityInterface::flags_
private

Definition at line 23 of file RosReflexxesVelocityInterface.h.

boost::shared_ptr<RMLVelocityInputParameters> RosReflexxesVelocityInterface::input_params_
private

Definition at line 24 of file RosReflexxesVelocityInterface.h.

std::vector<double> RosReflexxesVelocityInterface::max_acceleration_
private

Definition at line 20 of file RosReflexxesVelocityInterface.h.

std::vector<double> RosReflexxesVelocityInterface::max_jerk_
private

Definition at line 21 of file RosReflexxesVelocityInterface.h.

std::vector<double> RosReflexxesVelocityInterface::max_velocities_
private

Definition at line 19 of file RosReflexxesVelocityInterface.h.

int RosReflexxesVelocityInterface::n_dim_
private

Definition at line 17 of file RosReflexxesVelocityInterface.h.

ros::NodeHandle RosReflexxesVelocityInterface::nh_
private

Definition at line 15 of file RosReflexxesVelocityInterface.h.

boost::shared_ptr<RMLVelocityOutputParameters> RosReflexxesVelocityInterface::output_params_
private

Definition at line 25 of file RosReflexxesVelocityInterface.h.

double RosReflexxesVelocityInterface::period_
private

Definition at line 18 of file RosReflexxesVelocityInterface.h.

bool RosReflexxesVelocityInterface::position_initialized_
private

Definition at line 27 of file RosReflexxesVelocityInterface.h.

boost::shared_ptr<ReflexxesAPI> RosReflexxesVelocityInterface::rml_
private

Definition at line 26 of file RosReflexxesVelocityInterface.h.


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


ros_reflexxes
Author(s):
autogenerated on Sat Nov 21 2020 03:17:43