Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
robotis_op::WalkingModule Class Reference

#include <op3_walking_module.h>

Inheritance diagram for robotis_op::WalkingModule:
Inheritance graph
[legend]

Public Types

enum  { PHASE0 = 0, PHASE1 = 1, PHASE2 = 2, PHASE3 = 3 }
 

Public Member Functions

double getBodySwingY ()
 
double getBodySwingZ ()
 
int getCurrentPhase ()
 
void initialize (const int control_cycle_msec, robotis_framework::Robot *robot)
 
bool isRunning ()
 
void onModuleDisable ()
 
void onModuleEnable ()
 
void process (std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors)
 
void stop ()
 
 WalkingModule ()
 
virtual ~WalkingModule ()
 
- Public Member Functions inherited from robotis_framework::MotionModule
ControlMode getControlMode ()
 
bool getModuleEnable ()
 
std::string getModuleName ()
 
void setModuleEnable (bool enable)
 
virtual ~MotionModule ()
 

Private Types

enum  { WalkingDisable = 0, WalkingEnable = 1, WalkingInitPose = 2, WalkingReady = 3 }
 

Private Member Functions

void computeArmAngle (double *arm_angle)
 
bool computeIK (double *out, double x, double y, double z, double a, double b, double c)
 
bool computeLegAngle (double *leg_angle)
 
bool getWalkigParameterCallback (op3_walking_module_msgs::GetWalkingParam::Request &req, op3_walking_module_msgs::GetWalkingParam::Response &res)
 
void iniPoseTraGene (double mov_time)
 
void loadWalkingParam (const std::string &path)
 
void processPhase (const double &time_unit)
 
void publishStatusMsg (unsigned int type, std::string msg)
 
void queueThread ()
 
void saveWalkingParam (std::string &path)
 
void sensoryFeedback (const double &rlGyroErr, const double &fbGyroErr, double *balance_angle)
 
void startWalking ()
 
void updateMovementParam ()
 
void updatePoseParam ()
 
void updateTimeParam ()
 
void walkingCommandCallback (const std_msgs::String::ConstPtr &msg)
 
void walkingParameterCallback (const op3_walking_module_msgs::WalkingParam::ConstPtr &msg)
 
double wSin (double time, double period, double period_shift, double mag, double mag_shift)
 

Private Attributes

double a_move_amplitude_
 
double a_move_amplitude_shift_
 
double a_move_period_time_
 
double a_move_phase_shift_
 
double a_offset_
 
double arm_swing_gain_
 
double body_swing_y
 
double body_swing_z
 
Eigen::MatrixXd calc_joint_tra_
 
int control_cycle_msec_
 
bool ctrl_running_
 
const bool DEBUG
 
double dsp_ratio_
 
Eigen::MatrixXd goal_position_
 
double hit_pitch_offset_
 
int init_pose_count_
 
Eigen::MatrixXd init_position_
 
Eigen::MatrixXi joint_axis_direction_
 
std::map< std::string, int > joint_table_
 
double l_ssp_end_time_
 
double l_ssp_start_time_
 
OP3KinematicsDynamicsop3_kd_
 
double p_offset_
 
std::string param_path_
 
double pelvis_offset_
 
double pelvis_swing_
 
double period_time_
 
double phase1_time_
 
double phase2_time_
 
double phase3_time_
 
int phase_
 
double previous_x_move_amplitude_
 
boost::mutex publish_mutex_
 
boost::thread queue_thread_
 
double r_offset_
 
double r_ssp_end_time_
 
double r_ssp_start_time_
 
bool real_running_
 
ros::Publisher robot_pose_pub_
 
double ssp_ratio_
 
double ssp_time_
 
ros::Publisher status_msg_pub_
 
Eigen::MatrixXd target_position_
 
double time_
 
op3_walking_module_msgs::WalkingParam walking_param_
 
int walking_state_
 
double x_move_amplitude_
 
double x_move_amplitude_shift_
 
double x_move_period_time_
 
double x_move_phase_shift_
 
double x_offset_
 
double x_swap_amplitude_
 
double x_swap_amplitude_shift_
 
double x_swap_period_time_
 
double x_swap_phase_shift_
 
double y_move_amplitude_
 
double y_move_amplitude_shift_
 
double y_move_period_time_
 
double y_move_phase_shift_
 
double y_offset_
 
double y_swap_amplitude_
 
double y_swap_amplitude_shift_
 
double y_swap_period_time_
 
double y_swap_phase_shift_
 
double z_move_amplitude_
 
double z_move_amplitude_shift_
 
double z_move_period_time_
 
double z_move_phase_shift_
 
double z_offset_
 
double z_swap_amplitude_
 
double z_swap_amplitude_shift_
 
double z_swap_period_time_
 
double z_swap_phase_shift_
 

Additional Inherited Members

- Static Public Member Functions inherited from robotis_framework::Singleton< WalkingModule >
static void destroyInstance ()
 
static T * getInstance ()
 
- Public Attributes inherited from robotis_framework::MotionModule
std::map< std::string, DynamixelState * > result_
 
- Protected Member Functions inherited from robotis_framework::Singleton< WalkingModule >
Singletonoperator= (Singleton const &)
 
 Singleton (Singleton const &)
 
 Singleton ()
 
- Protected Attributes inherited from robotis_framework::MotionModule
ControlMode control_mode_
 
bool enable_
 
std::string module_name_
 

Detailed Description

Definition at line 61 of file op3_walking_module.h.

Member Enumeration Documentation

anonymous enum
Enumerator
PHASE0 
PHASE1 
PHASE2 
PHASE3 

Definition at line 65 of file op3_walking_module.h.

anonymous enum
private
Enumerator
WalkingDisable 
WalkingEnable 
WalkingInitPose 
WalkingReady 

Definition at line 97 of file op3_walking_module.h.

Constructor & Destructor Documentation

robotis_op::WalkingModule::WalkingModule ( )

Definition at line 24 of file op3_walking_module.cpp.

robotis_op::WalkingModule::~WalkingModule ( )
virtual

Definition at line 80 of file op3_walking_module.cpp.

Member Function Documentation

void robotis_op::WalkingModule::computeArmAngle ( double *  arm_angle)
private

Definition at line 863 of file op3_walking_module.cpp.

bool robotis_op::WalkingModule::computeIK ( double *  out,
double  x,
double  y,
double  z,
double  a,
double  b,
double  c 
)
private

Definition at line 237 of file op3_walking_module.cpp.

bool robotis_op::WalkingModule::computeLegAngle ( double *  leg_angle)
private

Definition at line 625 of file op3_walking_module.cpp.

double robotis_op::WalkingModule::getBodySwingY ( )
inline

Definition at line 87 of file op3_walking_module.h.

double robotis_op::WalkingModule::getBodySwingZ ( )
inline

Definition at line 91 of file op3_walking_module.h.

int robotis_op::WalkingModule::getCurrentPhase ( )
inline

Definition at line 83 of file op3_walking_module.h.

bool robotis_op::WalkingModule::getWalkigParameterCallback ( op3_walking_module_msgs::GetWalkingParam::Request &  req,
op3_walking_module_msgs::GetWalkingParam::Response &  res 
)
private

Definition at line 222 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::iniPoseTraGene ( double  mov_time)
private

Definition at line 1006 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::initialize ( const int  control_cycle_msec,
robotis_framework::Robot robot 
)
virtual

Implements robotis_framework::MotionModule.

Definition at line 85 of file op3_walking_module.cpp.

bool robotis_op::WalkingModule::isRunning ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 418 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::loadWalkingParam ( const std::string &  path)
private

Definition at line 910 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::onModuleDisable ( )
virtual

Reimplemented from robotis_framework::MotionModule.

Definition at line 1000 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::onModuleEnable ( )
virtual

Reimplemented from robotis_framework::MotionModule.

Definition at line 994 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::process ( std::map< std::string, robotis_framework::Dynamixel * >  dxls,
std::map< std::string, double >  sensors 
)
virtual

Implements robotis_framework::MotionModule.

Definition at line 424 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::processPhase ( const double &  time_unit)
private

Definition at line 568 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::publishStatusMsg ( unsigned int  type,
std::string  msg 
)
private

Definition at line 186 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::queueThread ( )
private

Definition at line 160 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::saveWalkingParam ( std::string &  path)
private

Definition at line 959 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::sensoryFeedback ( const double &  rlGyroErr,
const double &  fbGyroErr,
double *  balance_angle 
)
private

Definition at line 880 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::startWalking ( )
private

Definition at line 404 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::stop ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 412 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::updateMovementParam ( )
private

Definition at line 349 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::updatePoseParam ( )
private

Definition at line 393 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::updateTimeParam ( )
private

Definition at line 320 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::walkingCommandCallback ( const std_msgs::String::ConstPtr &  msg)
private

Definition at line 197 of file op3_walking_module.cpp.

void robotis_op::WalkingModule::walkingParameterCallback ( const op3_walking_module_msgs::WalkingParam::ConstPtr &  msg)
private

Definition at line 217 of file op3_walking_module.cpp.

double robotis_op::WalkingModule::wSin ( double  time,
double  period,
double  period_shift,
double  mag,
double  mag_shift 
)
private

Definition at line 230 of file op3_walking_module.cpp.

Member Data Documentation

double robotis_op::WalkingModule::a_move_amplitude_
private

Definition at line 200 of file op3_walking_module.h.

double robotis_op::WalkingModule::a_move_amplitude_shift_
private

Definition at line 201 of file op3_walking_module.h.

double robotis_op::WalkingModule::a_move_period_time_
private

Definition at line 164 of file op3_walking_module.h.

double robotis_op::WalkingModule::a_move_phase_shift_
private

Definition at line 199 of file op3_walking_module.h.

double robotis_op::WalkingModule::a_offset_
private

Definition at line 179 of file op3_walking_module.h.

double robotis_op::WalkingModule::arm_swing_gain_
private

Definition at line 206 of file op3_walking_module.h.

double robotis_op::WalkingModule::body_swing_y
private

Definition at line 213 of file op3_walking_module.h.

double robotis_op::WalkingModule::body_swing_z
private

Definition at line 214 of file op3_walking_module.h.

Eigen::MatrixXd robotis_op::WalkingModule::calc_joint_tra_
private

Definition at line 142 of file op3_walking_module.h.

int robotis_op::WalkingModule::control_cycle_msec_
private

Definition at line 133 of file op3_walking_module.h.

bool robotis_op::WalkingModule::ctrl_running_
private

Definition at line 208 of file op3_walking_module.h.

const bool robotis_op::WalkingModule::DEBUG
private

Definition at line 105 of file op3_walking_module.h.

double robotis_op::WalkingModule::dsp_ratio_
private

Definition at line 156 of file op3_walking_module.h.

Eigen::MatrixXd robotis_op::WalkingModule::goal_position_
private

Definition at line 145 of file op3_walking_module.h.

double robotis_op::WalkingModule::hit_pitch_offset_
private

Definition at line 205 of file op3_walking_module.h.

int robotis_op::WalkingModule::init_pose_count_
private

Definition at line 150 of file op3_walking_module.h.

Eigen::MatrixXd robotis_op::WalkingModule::init_position_
private

Definition at line 146 of file op3_walking_module.h.

Eigen::MatrixXi robotis_op::WalkingModule::joint_axis_direction_
private

Definition at line 147 of file op3_walking_module.h.

std::map<std::string, int> robotis_op::WalkingModule::joint_table_
private

Definition at line 148 of file op3_walking_module.h.

double robotis_op::WalkingModule::l_ssp_end_time_
private

Definition at line 167 of file op3_walking_module.h.

double robotis_op::WalkingModule::l_ssp_start_time_
private

Definition at line 166 of file op3_walking_module.h.

OP3KinematicsDynamics* robotis_op::WalkingModule::op3_kd_
private

Definition at line 132 of file op3_walking_module.h.

double robotis_op::WalkingModule::p_offset_
private

Definition at line 178 of file op3_walking_module.h.

std::string robotis_op::WalkingModule::param_path_
private

Definition at line 134 of file op3_walking_module.h.

double robotis_op::WalkingModule::pelvis_offset_
private

Definition at line 203 of file op3_walking_module.h.

double robotis_op::WalkingModule::pelvis_swing_
private

Definition at line 204 of file op3_walking_module.h.

double robotis_op::WalkingModule::period_time_
private

Definition at line 155 of file op3_walking_module.h.

double robotis_op::WalkingModule::phase1_time_
private

Definition at line 170 of file op3_walking_module.h.

double robotis_op::WalkingModule::phase2_time_
private

Definition at line 171 of file op3_walking_module.h.

double robotis_op::WalkingModule::phase3_time_
private

Definition at line 172 of file op3_walking_module.h.

int robotis_op::WalkingModule::phase_
private

Definition at line 212 of file op3_walking_module.h.

double robotis_op::WalkingModule::previous_x_move_amplitude_
private

Definition at line 152 of file op3_walking_module.h.

boost::mutex robotis_op::WalkingModule::publish_mutex_
private

Definition at line 136 of file op3_walking_module.h.

boost::thread robotis_op::WalkingModule::queue_thread_
private

Definition at line 135 of file op3_walking_module.h.

double robotis_op::WalkingModule::r_offset_
private

Definition at line 177 of file op3_walking_module.h.

double robotis_op::WalkingModule::r_ssp_end_time_
private

Definition at line 169 of file op3_walking_module.h.

double robotis_op::WalkingModule::r_ssp_start_time_
private

Definition at line 168 of file op3_walking_module.h.

bool robotis_op::WalkingModule::real_running_
private

Definition at line 209 of file op3_walking_module.h.

ros::Publisher robotis_op::WalkingModule::robot_pose_pub_
private

Definition at line 139 of file op3_walking_module.h.

double robotis_op::WalkingModule::ssp_ratio_
private

Definition at line 157 of file op3_walking_module.h.

double robotis_op::WalkingModule::ssp_time_
private

Definition at line 165 of file op3_walking_module.h.

ros::Publisher robotis_op::WalkingModule::status_msg_pub_
private

Definition at line 140 of file op3_walking_module.h.

Eigen::MatrixXd robotis_op::WalkingModule::target_position_
private

Definition at line 144 of file op3_walking_module.h.

double robotis_op::WalkingModule::time_
private

Definition at line 210 of file op3_walking_module.h.

op3_walking_module_msgs::WalkingParam robotis_op::WalkingModule::walking_param_
private

Definition at line 151 of file op3_walking_module.h.

int robotis_op::WalkingModule::walking_state_
private

Definition at line 149 of file op3_walking_module.h.

double robotis_op::WalkingModule::x_move_amplitude_
private

Definition at line 185 of file op3_walking_module.h.

double robotis_op::WalkingModule::x_move_amplitude_shift_
private

Definition at line 186 of file op3_walking_module.h.

double robotis_op::WalkingModule::x_move_period_time_
private

Definition at line 159 of file op3_walking_module.h.

double robotis_op::WalkingModule::x_move_phase_shift_
private

Definition at line 184 of file op3_walking_module.h.

double robotis_op::WalkingModule::x_offset_
private

Definition at line 174 of file op3_walking_module.h.

double robotis_op::WalkingModule::x_swap_amplitude_
private

Definition at line 182 of file op3_walking_module.h.

double robotis_op::WalkingModule::x_swap_amplitude_shift_
private

Definition at line 183 of file op3_walking_module.h.

double robotis_op::WalkingModule::x_swap_period_time_
private

Definition at line 158 of file op3_walking_module.h.

double robotis_op::WalkingModule::x_swap_phase_shift_
private

Definition at line 181 of file op3_walking_module.h.

double robotis_op::WalkingModule::y_move_amplitude_
private

Definition at line 191 of file op3_walking_module.h.

double robotis_op::WalkingModule::y_move_amplitude_shift_
private

Definition at line 192 of file op3_walking_module.h.

double robotis_op::WalkingModule::y_move_period_time_
private

Definition at line 161 of file op3_walking_module.h.

double robotis_op::WalkingModule::y_move_phase_shift_
private

Definition at line 190 of file op3_walking_module.h.

double robotis_op::WalkingModule::y_offset_
private

Definition at line 175 of file op3_walking_module.h.

double robotis_op::WalkingModule::y_swap_amplitude_
private

Definition at line 188 of file op3_walking_module.h.

double robotis_op::WalkingModule::y_swap_amplitude_shift_
private

Definition at line 189 of file op3_walking_module.h.

double robotis_op::WalkingModule::y_swap_period_time_
private

Definition at line 160 of file op3_walking_module.h.

double robotis_op::WalkingModule::y_swap_phase_shift_
private

Definition at line 187 of file op3_walking_module.h.

double robotis_op::WalkingModule::z_move_amplitude_
private

Definition at line 197 of file op3_walking_module.h.

double robotis_op::WalkingModule::z_move_amplitude_shift_
private

Definition at line 198 of file op3_walking_module.h.

double robotis_op::WalkingModule::z_move_period_time_
private

Definition at line 163 of file op3_walking_module.h.

double robotis_op::WalkingModule::z_move_phase_shift_
private

Definition at line 196 of file op3_walking_module.h.

double robotis_op::WalkingModule::z_offset_
private

Definition at line 176 of file op3_walking_module.h.

double robotis_op::WalkingModule::z_swap_amplitude_
private

Definition at line 194 of file op3_walking_module.h.

double robotis_op::WalkingModule::z_swap_amplitude_shift_
private

Definition at line 195 of file op3_walking_module.h.

double robotis_op::WalkingModule::z_swap_period_time_
private

Definition at line 162 of file op3_walking_module.h.

double robotis_op::WalkingModule::z_swap_phase_shift_
private

Definition at line 193 of file op3_walking_module.h.


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


op3_walking_module
Author(s): Kayman
autogenerated on Mon Jun 10 2019 14:41:25