Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
thormang3::FootStepGenerator Class Reference

#include <robotis_foot_step_generator.h>

Public Member Functions

void calcLeftKickStep (thormang3_walking_module_msgs::AddStepDataArray::Request::_step_data_array_type *step_data_array, const thormang3_walking_module_msgs::StepData &ref_step_data)
 
void calcRightKickStep (thormang3_walking_module_msgs::AddStepDataArray::Request::_step_data_array_type *step_data_array, const thormang3_walking_module_msgs::StepData &ref_step_data)
 
 FootStepGenerator ()
 
void getStepData (thormang3_walking_module_msgs::AddStepDataArray::Request::_step_data_array_type *step_data_array, const thormang3_walking_module_msgs::StepData &ref_step_data, int desired_step_type)
 
void getStepDataFromStepData2DArray (thormang3_walking_module_msgs::AddStepDataArray::Request::_step_data_array_type *step_data_array, const thormang3_walking_module_msgs::StepData &ref_step_data, const thormang3_foot_step_generator::Step2DArray::ConstPtr &request_step_2d)
 
void initialize ()
 
 ~FootStepGenerator ()
 

Public Attributes

double body_z_swap_m_
 
double default_y_feet_offset_m_
 
double dsp_ratio_
 
double fb_step_length_m_
 
double foot_z_swap_m_
 
int num_of_step_
 
double rl_step_length_m_
 
double rotate_step_angle_rad_
 
double start_end_time_sec_
 
double step_time_sec_
 

Private Member Functions

void calcFBStep (const thormang3_walking_module_msgs::StepData &ref_step_data, int direction)
 
void calcRLStep (const thormang3_walking_module_msgs::StepData &ref_step_data, int direction)
 
void calcRoStep (const thormang3_walking_module_msgs::StepData &ref_step_data, int direction)
 
bool calcStep (const thormang3_walking_module_msgs::StepData &ref_step_data, int previous_step_type, int desired_step_type)
 
void calcStopStep (const thormang3_walking_module_msgs::StepData &ref_step_data, int direction)
 
Eigen::MatrixXd getInverseTransformation (Eigen::MatrixXd transform)
 
void getPosefromTransformMatrix (const Eigen::MatrixXd &matTransform, double *position_x, double *position_y, double *position_z, double *roll, double *pitch, double *yaw)
 
thormang3_walking_module_msgs::PoseXYZRPY getPosefromTransformMatrix (const Eigen::MatrixXd &matTransform)
 
Eigen::MatrixXd getTransformationXYZRPY (double position_x, double position_y, double position_z, double roll, double pitch, double yaw)
 

Private Attributes

int previous_step_type_
 
thormang3_walking_module_msgs::AddStepDataArray::Request::_step_data_array_type step_data_array_
 

Detailed Description

Definition at line 45 of file robotis_foot_step_generator.h.

Constructor & Destructor Documentation

FootStepGenerator::FootStepGenerator ( )

Definition at line 56 of file robotis_foot_step_generator.cpp.

FootStepGenerator::~FootStepGenerator ( )

Definition at line 78 of file robotis_foot_step_generator.cpp.

Member Function Documentation

void FootStepGenerator::calcFBStep ( const thormang3_walking_module_msgs::StepData &  ref_step_data,
int  direction 
)
private

Definition at line 615 of file robotis_foot_step_generator.cpp.

void FootStepGenerator::calcLeftKickStep ( thormang3_walking_module_msgs::AddStepDataArray::Request::_step_data_array_type *  step_data_array,
const thormang3_walking_module_msgs::StepData &  ref_step_data 
)

Definition at line 1147 of file robotis_foot_step_generator.cpp.

void FootStepGenerator::calcRightKickStep ( thormang3_walking_module_msgs::AddStepDataArray::Request::_step_data_array_type *  step_data_array,
const thormang3_walking_module_msgs::StepData &  ref_step_data 
)

Definition at line 1066 of file robotis_foot_step_generator.cpp.

void FootStepGenerator::calcRLStep ( const thormang3_walking_module_msgs::StepData &  ref_step_data,
int  direction 
)
private

Definition at line 726 of file robotis_foot_step_generator.cpp.

void FootStepGenerator::calcRoStep ( const thormang3_walking_module_msgs::StepData &  ref_step_data,
int  direction 
)
private

Definition at line 852 of file robotis_foot_step_generator.cpp.

bool FootStepGenerator::calcStep ( const thormang3_walking_module_msgs::StepData &  ref_step_data,
int  previous_step_type,
int  desired_step_type 
)
private

Definition at line 304 of file robotis_foot_step_generator.cpp.

void FootStepGenerator::calcStopStep ( const thormang3_walking_module_msgs::StepData &  ref_step_data,
int  direction 
)
private

Definition at line 1053 of file robotis_foot_step_generator.cpp.

Eigen::MatrixXd FootStepGenerator::getInverseTransformation ( Eigen::MatrixXd  transform)
private

Definition at line 158 of file robotis_foot_step_generator.cpp.

void FootStepGenerator::getPosefromTransformMatrix ( const Eigen::MatrixXd &  matTransform,
double *  position_x,
double *  position_y,
double *  position_z,
double *  roll,
double *  pitch,
double *  yaw 
)
private

Definition at line 125 of file robotis_foot_step_generator.cpp.

thormang3_walking_module_msgs::PoseXYZRPY FootStepGenerator::getPosefromTransformMatrix ( const Eigen::MatrixXd &  matTransform)
private

Definition at line 135 of file robotis_foot_step_generator.cpp.

void FootStepGenerator::getStepData ( thormang3_walking_module_msgs::AddStepDataArray::Request::_step_data_array_type *  step_data_array,
const thormang3_walking_module_msgs::StepData &  ref_step_data,
int  desired_step_type 
)

Definition at line 183 of file robotis_foot_step_generator.cpp.

void FootStepGenerator::getStepDataFromStepData2DArray ( thormang3_walking_module_msgs::AddStepDataArray::Request::_step_data_array_type *  step_data_array,
const thormang3_walking_module_msgs::StepData &  ref_step_data,
const thormang3_foot_step_generator::Step2DArray::ConstPtr &  request_step_2d 
)

Definition at line 204 of file robotis_foot_step_generator.cpp.

Eigen::MatrixXd FootStepGenerator::getTransformationXYZRPY ( double  position_x,
double  position_y,
double  position_z,
double  roll,
double  pitch,
double  yaw 
)
private

Definition at line 87 of file robotis_foot_step_generator.cpp.

void FootStepGenerator::initialize ( )

Definition at line 81 of file robotis_foot_step_generator.cpp.

Member Data Documentation

double thormang3::FootStepGenerator::body_z_swap_m_

Definition at line 76 of file robotis_foot_step_generator.h.

double thormang3::FootStepGenerator::default_y_feet_offset_m_

Definition at line 78 of file robotis_foot_step_generator.h.

double thormang3::FootStepGenerator::dsp_ratio_

Definition at line 73 of file robotis_foot_step_generator.h.

double thormang3::FootStepGenerator::fb_step_length_m_

Definition at line 67 of file robotis_foot_step_generator.h.

double thormang3::FootStepGenerator::foot_z_swap_m_

Definition at line 75 of file robotis_foot_step_generator.h.

int thormang3::FootStepGenerator::num_of_step_

Definition at line 66 of file robotis_foot_step_generator.h.

int thormang3::FootStepGenerator::previous_step_type_
private

Definition at line 95 of file robotis_foot_step_generator.h.

double thormang3::FootStepGenerator::rl_step_length_m_

Definition at line 68 of file robotis_foot_step_generator.h.

double thormang3::FootStepGenerator::rotate_step_angle_rad_

Definition at line 69 of file robotis_foot_step_generator.h.

double thormang3::FootStepGenerator::start_end_time_sec_

Definition at line 72 of file robotis_foot_step_generator.h.

thormang3_walking_module_msgs::AddStepDataArray::Request::_step_data_array_type thormang3::FootStepGenerator::step_data_array_
private

Definition at line 93 of file robotis_foot_step_generator.h.

double thormang3::FootStepGenerator::step_time_sec_

Definition at line 71 of file robotis_foot_step_generator.h.


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


thormang3_foot_step_generator
Author(s): Kayman , Jay Song
autogenerated on Mon Jun 10 2019 15:38:28