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

#include <walking_module.h>

Inheritance diagram for thormang3::OnlineWalkingModule:
Inheritance graph
[legend]

Public Member Functions

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

Public Attributes

double gyro_pitch_
 
double gyro_roll_
 
double l_foot_fx_N_
 
double l_foot_fy_N_
 
double l_foot_fz_N_
 
double l_foot_Tx_Nm_
 
double l_foot_Ty_Nm_
 
double l_foot_Tz_Nm_
 
double orientation_pitch_
 
double orientation_roll_
 
double r_foot_fx_N_
 
double r_foot_fy_N_
 
double r_foot_fz_N_
 
double r_foot_Tx_Nm_
 
double r_foot_Ty_Nm_
 
double r_foot_Tz_Nm_
 
- Public Attributes inherited from robotis_framework::MotionModule
std::map< std::string, DynamixelState * > result_
 

Private Member Functions

bool addStepDataServiceCallback (thormang3_walking_module_msgs::AddStepDataArray::Request &req, thormang3_walking_module_msgs::AddStepDataArray::Response &res)
 
bool checkBalanceOnOff ()
 
int convertStepDataMsgToStepData (thormang3_walking_module_msgs::StepData &src, robotis_framework::StepData &des)
 
int convertStepDataToStepDataMsg (robotis_framework::StepData &src, thormang3_walking_module_msgs::StepData &des)
 
bool getReferenceStepDataServiceCallback (thormang3_walking_module_msgs::GetReferenceStepData::Request &req, thormang3_walking_module_msgs::GetReferenceStepData::Response &res)
 
void imuDataOutputCallback (const sensor_msgs::Imu::ConstPtr &msg)
 
bool IsRunningServiceCallback (thormang3_walking_module_msgs::IsRunning::Request &req, thormang3_walking_module_msgs::IsRunning::Response &res)
 
void publishDoneMsg (std::string msg)
 
void publishRobotPose (void)
 
void publishStatusMsg (unsigned int type, std::string msg)
 
void publishWalkingTuningData ()
 
void queueThread ()
 
bool removeExistingStepDataServiceCallback (thormang3_walking_module_msgs::RemoveExistingStepData::Request &req, thormang3_walking_module_msgs::RemoveExistingStepData::Response &res)
 
void setBalanceParam (thormang3_walking_module_msgs::BalanceParam &balance_param_msg)
 
bool setBalanceParamServiceCallback (thormang3_walking_module_msgs::SetBalanceParam::Request &req, thormang3_walking_module_msgs::SetBalanceParam::Response &res)
 
void setJointFeedBackGain (thormang3_walking_module_msgs::JointFeedBackGain &msg)
 
bool setJointFeedBackGainServiceCallback (thormang3_walking_module_msgs::SetJointFeedBackGain::Request &req, thormang3_walking_module_msgs::SetJointFeedBackGain::Response &res)
 
bool startWalkingServiceCallback (thormang3_walking_module_msgs::StartWalking::Request &req, thormang3_walking_module_msgs::StartWalking::Response &res)
 
void updateBalanceParam ()
 
void updateJointFeedBackGain ()
 

Private Attributes

double balance_update_duration_
 
Eigen::MatrixXd balance_update_polynomial_coeff_
 
double balance_update_sys_time_
 
bool balance_update_with_loop_
 
int control_cycle_msec_
 
thormang3_walking_module_msgs::BalanceParam current_balance_param_
 
thormang3_walking_module_msgs::JointFeedBackGain current_joint_feedback_gain_
 
thormang3_walking_module_msgs::BalanceParam desired_balance_param_
 
thormang3_walking_module_msgs::JointFeedBackGain desired_joint_feedback_gain_
 
Eigen::MatrixXd desired_matrix_g_to_cob_
 
Eigen::MatrixXd desired_matrix_g_to_lfoot_
 
Eigen::MatrixXd desired_matrix_g_to_rfoot_
 
ros::Publisher done_msg_pub_
 
ros::Publisher ft_states_pub_
 
bool gazebo_
 
ros::Publisher imu_orientation_states_pub_
 
double joint_feedback_update_duration_
 
Eigen::MatrixXd joint_feedback_update_polynomial_coeff_
 
double joint_feedback_update_sys_time_
 
bool joint_feedback_update_with_loop_
 
std::map< std::string, int > joint_name_to_index_
 
int l_foot_ft_publish_checker_
 
ros::Publisher pelvis_base_msg_pub_
 
bool present_running
 
thormang3_walking_module_msgs::BalanceParam previous_balance_param_
 
thormang3_walking_module_msgs::JointFeedBackGain previous_joint_feedback_gain_
 
bool previous_running_
 
boost::mutex process_mutex_
 
boost::thread queue_thread_
 
int r_foot_ft_publish_checker_
 
thormang3_walking_module_msgs::RobotPose robot_pose_msg_
 
ros::Publisher robot_pose_pub_
 
Eigen::MatrixXd rot_x_pi_3d_
 
Eigen::MatrixXd rot_z_pi_3d_
 
ros::Publisher status_msg_pub_
 
thormang3_walking_module_msgs::WalkingJointStatesStamped walking_joint_states_msg_
 
ros::Publisher walking_joint_states_pub_
 

Additional Inherited Members

- Static Public Member Functions inherited from robotis_framework::Singleton< OnlineWalkingModule >
static void destroyInstance ()
 
static T * getInstance ()
 
- Protected Member Functions inherited from robotis_framework::Singleton< OnlineWalkingModule >
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 57 of file walking_module.h.

Constructor & Destructor Documentation

OnlineWalkingModule::OnlineWalkingModule ( )

Definition at line 57 of file walking_module.cpp.

OnlineWalkingModule::~OnlineWalkingModule ( )
virtual

Definition at line 143 of file walking_module.cpp.

Member Function Documentation

bool OnlineWalkingModule::addStepDataServiceCallback ( thormang3_walking_module_msgs::AddStepDataArray::Request &  req,
thormang3_walking_module_msgs::AddStepDataArray::Response &  res 
)
private

Definition at line 456 of file walking_module.cpp.

bool OnlineWalkingModule::checkBalanceOnOff ( )
private

Definition at line 1002 of file walking_module.cpp.

int OnlineWalkingModule::convertStepDataMsgToStepData ( thormang3_walking_module_msgs::StepData &  src,
robotis_framework::StepData des 
)
private

Definition at line 318 of file walking_module.cpp.

int OnlineWalkingModule::convertStepDataToStepDataMsg ( robotis_framework::StepData src,
thormang3_walking_module_msgs::StepData &  des 
)
private

Definition at line 404 of file walking_module.cpp.

bool OnlineWalkingModule::getReferenceStepDataServiceCallback ( thormang3_walking_module_msgs::GetReferenceStepData::Request &  req,
thormang3_walking_module_msgs::GetReferenceStepData::Response &  res 
)
private

Definition at line 442 of file walking_module.cpp.

void OnlineWalkingModule::imuDataOutputCallback ( const sensor_msgs::Imu::ConstPtr &  msg)
private

Definition at line 1067 of file walking_module.cpp.

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

Implements robotis_framework::MotionModule.

Definition at line 148 of file walking_module.cpp.

bool OnlineWalkingModule::isRunning ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 603 of file walking_module.cpp.

bool OnlineWalkingModule::IsRunningServiceCallback ( thormang3_walking_module_msgs::IsRunning::Request &  req,
thormang3_walking_module_msgs::IsRunning::Response &  res 
)
private

Definition at line 594 of file walking_module.cpp.

void OnlineWalkingModule::onModuleDisable ( )
virtual

Reimplemented from robotis_framework::MotionModule.

Definition at line 1084 of file walking_module.cpp.

void OnlineWalkingModule::onModuleEnable ( )
virtual

Reimplemented from robotis_framework::MotionModule.

Definition at line 1077 of file walking_module.cpp.

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

Implements robotis_framework::MotionModule.

Definition at line 1151 of file walking_module.cpp.

void OnlineWalkingModule::publishDoneMsg ( std::string  msg)
private

Definition at line 310 of file walking_module.cpp.

void OnlineWalkingModule::publishRobotPose ( void  )
private

Definition at line 255 of file walking_module.cpp.

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

Definition at line 299 of file walking_module.cpp.

void thormang3::OnlineWalkingModule::publishWalkingTuningData ( )
private
void OnlineWalkingModule::queueThread ( )
private

Definition at line 213 of file walking_module.cpp.

bool OnlineWalkingModule::removeExistingStepDataServiceCallback ( thormang3_walking_module_msgs::RemoveExistingStepData::Request &  req,
thormang3_walking_module_msgs::RemoveExistingStepData::Response &  res 
)
private

Definition at line 1045 of file walking_module.cpp.

void OnlineWalkingModule::setBalanceParam ( thormang3_walking_module_msgs::BalanceParam &  balance_param_msg)
private

Definition at line 819 of file walking_module.cpp.

bool OnlineWalkingModule::setBalanceParamServiceCallback ( thormang3_walking_module_msgs::SetBalanceParam::Request &  req,
thormang3_walking_module_msgs::SetBalanceParam::Response &  res 
)
private

Definition at line 690 of file walking_module.cpp.

void OnlineWalkingModule::setJointFeedBackGain ( thormang3_walking_module_msgs::JointFeedBackGain &  msg)
private

Definition at line 930 of file walking_module.cpp.

bool OnlineWalkingModule::setJointFeedBackGainServiceCallback ( thormang3_walking_module_msgs::SetJointFeedBackGain::Request &  req,
thormang3_walking_module_msgs::SetJointFeedBackGain::Response &  res 
)
private

Definition at line 608 of file walking_module.cpp.

bool OnlineWalkingModule::startWalkingServiceCallback ( thormang3_walking_module_msgs::StartWalking::Request &  req,
thormang3_walking_module_msgs::StartWalking::Response &  res 
)
private

Definition at line 555 of file walking_module.cpp.

void OnlineWalkingModule::stop ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 1332 of file walking_module.cpp.

void OnlineWalkingModule::updateBalanceParam ( )
private

Definition at line 883 of file walking_module.cpp.

void OnlineWalkingModule::updateJointFeedBackGain ( )
private

Definition at line 961 of file walking_module.cpp.

Member Data Documentation

double thormang3::OnlineWalkingModule::balance_update_duration_
private

Definition at line 152 of file walking_module.h.

Eigen::MatrixXd thormang3::OnlineWalkingModule::balance_update_polynomial_coeff_
private

Definition at line 154 of file walking_module.h.

double thormang3::OnlineWalkingModule::balance_update_sys_time_
private

Definition at line 153 of file walking_module.h.

bool thormang3::OnlineWalkingModule::balance_update_with_loop_
private

Definition at line 151 of file walking_module.h.

int thormang3::OnlineWalkingModule::control_cycle_msec_
private

Definition at line 125 of file walking_module.h.

thormang3_walking_module_msgs::BalanceParam thormang3::OnlineWalkingModule::current_balance_param_
private

Definition at line 167 of file walking_module.h.

thormang3_walking_module_msgs::JointFeedBackGain thormang3::OnlineWalkingModule::current_joint_feedback_gain_
private

Definition at line 163 of file walking_module.h.

thormang3_walking_module_msgs::BalanceParam thormang3::OnlineWalkingModule::desired_balance_param_
private

Definition at line 168 of file walking_module.h.

thormang3_walking_module_msgs::JointFeedBackGain thormang3::OnlineWalkingModule::desired_joint_feedback_gain_
private

Definition at line 164 of file walking_module.h.

Eigen::MatrixXd thormang3::OnlineWalkingModule::desired_matrix_g_to_cob_
private

Definition at line 130 of file walking_module.h.

Eigen::MatrixXd thormang3::OnlineWalkingModule::desired_matrix_g_to_lfoot_
private

Definition at line 132 of file walking_module.h.

Eigen::MatrixXd thormang3::OnlineWalkingModule::desired_matrix_g_to_rfoot_
private

Definition at line 131 of file walking_module.h.

ros::Publisher thormang3::OnlineWalkingModule::done_msg_pub_
private

Definition at line 142 of file walking_module.h.

ros::Publisher thormang3::OnlineWalkingModule::ft_states_pub_
private

Definition at line 146 of file walking_module.h.

bool thormang3::OnlineWalkingModule::gazebo_
private

Definition at line 124 of file walking_module.h.

double thormang3::OnlineWalkingModule::gyro_pitch_

Definition at line 72 of file walking_module.h.

double thormang3::OnlineWalkingModule::gyro_roll_

Definition at line 72 of file walking_module.h.

ros::Publisher thormang3::OnlineWalkingModule::imu_orientation_states_pub_
private

Definition at line 145 of file walking_module.h.

double thormang3::OnlineWalkingModule::joint_feedback_update_duration_
private

Definition at line 158 of file walking_module.h.

Eigen::MatrixXd thormang3::OnlineWalkingModule::joint_feedback_update_polynomial_coeff_
private

Definition at line 160 of file walking_module.h.

double thormang3::OnlineWalkingModule::joint_feedback_update_sys_time_
private

Definition at line 159 of file walking_module.h.

bool thormang3::OnlineWalkingModule::joint_feedback_update_with_loop_
private

Definition at line 157 of file walking_module.h.

std::map<std::string, int> thormang3::OnlineWalkingModule::joint_name_to_index_
private

Definition at line 122 of file walking_module.h.

int thormang3::OnlineWalkingModule::l_foot_ft_publish_checker_
private

Definition at line 138 of file walking_module.h.

double thormang3::OnlineWalkingModule::l_foot_fx_N_

Definition at line 76 of file walking_module.h.

double thormang3::OnlineWalkingModule::l_foot_fy_N_

Definition at line 76 of file walking_module.h.

double thormang3::OnlineWalkingModule::l_foot_fz_N_

Definition at line 76 of file walking_module.h.

double thormang3::OnlineWalkingModule::l_foot_Tx_Nm_

Definition at line 77 of file walking_module.h.

double thormang3::OnlineWalkingModule::l_foot_Ty_Nm_

Definition at line 77 of file walking_module.h.

double thormang3::OnlineWalkingModule::l_foot_Tz_Nm_

Definition at line 77 of file walking_module.h.

double thormang3::OnlineWalkingModule::orientation_pitch_

Definition at line 73 of file walking_module.h.

double thormang3::OnlineWalkingModule::orientation_roll_

Definition at line 73 of file walking_module.h.

ros::Publisher thormang3::OnlineWalkingModule::pelvis_base_msg_pub_
private

Definition at line 141 of file walking_module.h.

bool thormang3::OnlineWalkingModule::present_running
private

Definition at line 134 of file walking_module.h.

thormang3_walking_module_msgs::BalanceParam thormang3::OnlineWalkingModule::previous_balance_param_
private

Definition at line 166 of file walking_module.h.

thormang3_walking_module_msgs::JointFeedBackGain thormang3::OnlineWalkingModule::previous_joint_feedback_gain_
private

Definition at line 162 of file walking_module.h.

bool thormang3::OnlineWalkingModule::previous_running_
private

Definition at line 134 of file walking_module.h.

boost::mutex thormang3::OnlineWalkingModule::process_mutex_
private

Definition at line 127 of file walking_module.h.

boost::thread thormang3::OnlineWalkingModule::queue_thread_
private

Definition at line 126 of file walking_module.h.

int thormang3::OnlineWalkingModule::r_foot_ft_publish_checker_
private

Definition at line 137 of file walking_module.h.

double thormang3::OnlineWalkingModule::r_foot_fx_N_

Definition at line 74 of file walking_module.h.

double thormang3::OnlineWalkingModule::r_foot_fy_N_

Definition at line 74 of file walking_module.h.

double thormang3::OnlineWalkingModule::r_foot_fz_N_

Definition at line 74 of file walking_module.h.

double thormang3::OnlineWalkingModule::r_foot_Tx_Nm_

Definition at line 75 of file walking_module.h.

double thormang3::OnlineWalkingModule::r_foot_Ty_Nm_

Definition at line 75 of file walking_module.h.

double thormang3::OnlineWalkingModule::r_foot_Tz_Nm_

Definition at line 75 of file walking_module.h.

thormang3_walking_module_msgs::RobotPose thormang3::OnlineWalkingModule::robot_pose_msg_
private

Definition at line 150 of file walking_module.h.

ros::Publisher thormang3::OnlineWalkingModule::robot_pose_pub_
private

Definition at line 139 of file walking_module.h.

Eigen::MatrixXd thormang3::OnlineWalkingModule::rot_x_pi_3d_
private

Definition at line 129 of file walking_module.h.

Eigen::MatrixXd thormang3::OnlineWalkingModule::rot_z_pi_3d_
private

Definition at line 129 of file walking_module.h.

ros::Publisher thormang3::OnlineWalkingModule::status_msg_pub_
private

Definition at line 140 of file walking_module.h.

thormang3_walking_module_msgs::WalkingJointStatesStamped thormang3::OnlineWalkingModule::walking_joint_states_msg_
private

Definition at line 147 of file walking_module.h.

ros::Publisher thormang3::OnlineWalkingModule::walking_joint_states_pub_
private

Definition at line 144 of file walking_module.h.


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


thormang3_walking_module
Author(s): Zerom , SCH , Kayman , Jay Song
autogenerated on Mon Jun 10 2019 15:37:56