#include <walking_module.h>
|
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 () |
|
Definition at line 57 of file walking_module.h.
OnlineWalkingModule::OnlineWalkingModule |
( |
| ) |
|
OnlineWalkingModule::~OnlineWalkingModule |
( |
| ) |
|
|
virtual |
bool OnlineWalkingModule::addStepDataServiceCallback |
( |
thormang3_walking_module_msgs::AddStepDataArray::Request & |
req, |
|
|
thormang3_walking_module_msgs::AddStepDataArray::Response & |
res |
|
) |
| |
|
private |
bool OnlineWalkingModule::checkBalanceOnOff |
( |
| ) |
|
|
private |
int OnlineWalkingModule::convertStepDataMsgToStepData |
( |
thormang3_walking_module_msgs::StepData & |
src, |
|
|
robotis_framework::StepData & |
des |
|
) |
| |
|
private |
int OnlineWalkingModule::convertStepDataToStepDataMsg |
( |
robotis_framework::StepData & |
src, |
|
|
thormang3_walking_module_msgs::StepData & |
des |
|
) |
| |
|
private |
bool OnlineWalkingModule::getReferenceStepDataServiceCallback |
( |
thormang3_walking_module_msgs::GetReferenceStepData::Request & |
req, |
|
|
thormang3_walking_module_msgs::GetReferenceStepData::Response & |
res |
|
) |
| |
|
private |
void OnlineWalkingModule::imuDataOutputCallback |
( |
const sensor_msgs::Imu::ConstPtr & |
msg | ) |
|
|
private |
bool OnlineWalkingModule::isRunning |
( |
| ) |
|
|
virtual |
bool OnlineWalkingModule::IsRunningServiceCallback |
( |
thormang3_walking_module_msgs::IsRunning::Request & |
req, |
|
|
thormang3_walking_module_msgs::IsRunning::Response & |
res |
|
) |
| |
|
private |
void OnlineWalkingModule::onModuleDisable |
( |
| ) |
|
|
virtual |
void OnlineWalkingModule::onModuleEnable |
( |
| ) |
|
|
virtual |
void OnlineWalkingModule::publishDoneMsg |
( |
std::string |
msg | ) |
|
|
private |
void OnlineWalkingModule::publishRobotPose |
( |
void |
| ) |
|
|
private |
void OnlineWalkingModule::publishStatusMsg |
( |
unsigned int |
type, |
|
|
std::string |
msg |
|
) |
| |
|
private |
void thormang3::OnlineWalkingModule::publishWalkingTuningData |
( |
| ) |
|
|
private |
void OnlineWalkingModule::queueThread |
( |
| ) |
|
|
private |
bool OnlineWalkingModule::removeExistingStepDataServiceCallback |
( |
thormang3_walking_module_msgs::RemoveExistingStepData::Request & |
req, |
|
|
thormang3_walking_module_msgs::RemoveExistingStepData::Response & |
res |
|
) |
| |
|
private |
void OnlineWalkingModule::setBalanceParam |
( |
thormang3_walking_module_msgs::BalanceParam & |
balance_param_msg | ) |
|
|
private |
bool OnlineWalkingModule::setBalanceParamServiceCallback |
( |
thormang3_walking_module_msgs::SetBalanceParam::Request & |
req, |
|
|
thormang3_walking_module_msgs::SetBalanceParam::Response & |
res |
|
) |
| |
|
private |
void OnlineWalkingModule::setJointFeedBackGain |
( |
thormang3_walking_module_msgs::JointFeedBackGain & |
msg | ) |
|
|
private |
bool OnlineWalkingModule::setJointFeedBackGainServiceCallback |
( |
thormang3_walking_module_msgs::SetJointFeedBackGain::Request & |
req, |
|
|
thormang3_walking_module_msgs::SetJointFeedBackGain::Response & |
res |
|
) |
| |
|
private |
bool OnlineWalkingModule::startWalkingServiceCallback |
( |
thormang3_walking_module_msgs::StartWalking::Request & |
req, |
|
|
thormang3_walking_module_msgs::StartWalking::Response & |
res |
|
) |
| |
|
private |
void OnlineWalkingModule::stop |
( |
| ) |
|
|
virtual |
void OnlineWalkingModule::updateBalanceParam |
( |
| ) |
|
|
private |
void OnlineWalkingModule::updateJointFeedBackGain |
( |
| ) |
|
|
private |
double thormang3::OnlineWalkingModule::balance_update_duration_ |
|
private |
Eigen::MatrixXd thormang3::OnlineWalkingModule::balance_update_polynomial_coeff_ |
|
private |
double thormang3::OnlineWalkingModule::balance_update_sys_time_ |
|
private |
bool thormang3::OnlineWalkingModule::balance_update_with_loop_ |
|
private |
int thormang3::OnlineWalkingModule::control_cycle_msec_ |
|
private |
thormang3_walking_module_msgs::BalanceParam thormang3::OnlineWalkingModule::current_balance_param_ |
|
private |
thormang3_walking_module_msgs::JointFeedBackGain thormang3::OnlineWalkingModule::current_joint_feedback_gain_ |
|
private |
thormang3_walking_module_msgs::BalanceParam thormang3::OnlineWalkingModule::desired_balance_param_ |
|
private |
thormang3_walking_module_msgs::JointFeedBackGain thormang3::OnlineWalkingModule::desired_joint_feedback_gain_ |
|
private |
Eigen::MatrixXd thormang3::OnlineWalkingModule::desired_matrix_g_to_cob_ |
|
private |
Eigen::MatrixXd thormang3::OnlineWalkingModule::desired_matrix_g_to_lfoot_ |
|
private |
Eigen::MatrixXd thormang3::OnlineWalkingModule::desired_matrix_g_to_rfoot_ |
|
private |
bool thormang3::OnlineWalkingModule::gazebo_ |
|
private |
double thormang3::OnlineWalkingModule::gyro_pitch_ |
double thormang3::OnlineWalkingModule::gyro_roll_ |
ros::Publisher thormang3::OnlineWalkingModule::imu_orientation_states_pub_ |
|
private |
double thormang3::OnlineWalkingModule::joint_feedback_update_duration_ |
|
private |
Eigen::MatrixXd thormang3::OnlineWalkingModule::joint_feedback_update_polynomial_coeff_ |
|
private |
double thormang3::OnlineWalkingModule::joint_feedback_update_sys_time_ |
|
private |
bool thormang3::OnlineWalkingModule::joint_feedback_update_with_loop_ |
|
private |
std::map<std::string, int> thormang3::OnlineWalkingModule::joint_name_to_index_ |
|
private |
int thormang3::OnlineWalkingModule::l_foot_ft_publish_checker_ |
|
private |
double thormang3::OnlineWalkingModule::l_foot_fx_N_ |
double thormang3::OnlineWalkingModule::l_foot_fy_N_ |
double thormang3::OnlineWalkingModule::l_foot_fz_N_ |
double thormang3::OnlineWalkingModule::l_foot_Tx_Nm_ |
double thormang3::OnlineWalkingModule::l_foot_Ty_Nm_ |
double thormang3::OnlineWalkingModule::l_foot_Tz_Nm_ |
double thormang3::OnlineWalkingModule::orientation_pitch_ |
double thormang3::OnlineWalkingModule::orientation_roll_ |
bool thormang3::OnlineWalkingModule::present_running |
|
private |
thormang3_walking_module_msgs::BalanceParam thormang3::OnlineWalkingModule::previous_balance_param_ |
|
private |
thormang3_walking_module_msgs::JointFeedBackGain thormang3::OnlineWalkingModule::previous_joint_feedback_gain_ |
|
private |
bool thormang3::OnlineWalkingModule::previous_running_ |
|
private |
boost::mutex thormang3::OnlineWalkingModule::process_mutex_ |
|
private |
boost::thread thormang3::OnlineWalkingModule::queue_thread_ |
|
private |
int thormang3::OnlineWalkingModule::r_foot_ft_publish_checker_ |
|
private |
double thormang3::OnlineWalkingModule::r_foot_fx_N_ |
double thormang3::OnlineWalkingModule::r_foot_fy_N_ |
double thormang3::OnlineWalkingModule::r_foot_fz_N_ |
double thormang3::OnlineWalkingModule::r_foot_Tx_Nm_ |
double thormang3::OnlineWalkingModule::r_foot_Ty_Nm_ |
double thormang3::OnlineWalkingModule::r_foot_Tz_Nm_ |
thormang3_walking_module_msgs::RobotPose thormang3::OnlineWalkingModule::robot_pose_msg_ |
|
private |
Eigen::MatrixXd thormang3::OnlineWalkingModule::rot_x_pi_3d_ |
|
private |
Eigen::MatrixXd thormang3::OnlineWalkingModule::rot_z_pi_3d_ |
|
private |
thormang3_walking_module_msgs::WalkingJointStatesStamped thormang3::OnlineWalkingModule::walking_joint_states_msg_ |
|
private |
ros::Publisher thormang3::OnlineWalkingModule::walking_joint_states_pub_ |
|
private |
The documentation for this class was generated from the following files: