Public Types | Public Slots | Signals | Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
thormang3_demo::QNodeThor3 Class Reference

#include <qnode.hpp>

Inheritance diagram for thormang3_demo::QNodeThor3:
Inheritance graph
[legend]

Public Types

enum  LogLevel {
  Debug = 0, Info = 1, Warn = 2, Error = 3,
  Fatal = 4
}
 

Public Slots

void getJointControlModule ()
 
void getJointPose (std::string joint_name)
 
void getKinematicsPose (std::string group_name)
 
void getKinematicsPoseCallback (const geometry_msgs::Pose::ConstPtr &msg)
 
void setCurrentControlUI (int mode)
 

Signals

void loggingUpdated ()
 
void rosShutdown ()
 
void updateCurrJoint (double value)
 
void updateCurrOri (double x, double y, double z, double w)
 
void updateCurrPos (double x, double y, double z)
 
void updateDemoPoint (const geometry_msgs::Point point)
 
void updateDemoPose (const geometry_msgs::Pose pose)
 
void updateHeadJointsAngle (double pan, double tilt)
 
void updatePresentJointControlModules (std::vector< int > mode)
 

Public Member Functions

void assembleLidar ()
 
void clearFootsteps ()
 
void clearInteractiveMarker ()
 
void clearLog ()
 
void clearUsingModule ()
 
void enableControlModule (const std::string &mode)
 
bool getIDFromJointName (const std::string &joint_name, int &id)
 
bool getIDJointNameFromIndex (const int &index, int &id, std::string &joint_name)
 
void getInteractiveMarkerPose ()
 
bool getJointNameFromID (const int &id, std::string &joint_name)
 
int getJointTableSize ()
 
int getModuleIndex (const std::string &mode_name)
 
std::string getModuleName (const int &index)
 
int getModuleTableSize ()
 
bool init ()
 
void initFTCommand (std::string command)
 
bool isUsingModule (const std::string &module_name)
 
void kickDemo (const std::string &kick_foot)
 
void log (const LogLevel &level, const std::string &msg, std::string sender="Demo")
 
QStringListModel * loggingModel ()
 
void makeFootstepUsingPlanner ()
 
void makeFootstepUsingPlanner (const geometry_msgs::Pose &target_foot_pose)
 
void makeInteractiveMarker (const geometry_msgs::Pose &marker_pose)
 
void manipulationDemo (const int &index)
 
void moveInitPose ()
 
void playMotion (int motion_index, bool to_action_script=true)
 
 QNodeThor3 (int argc, char **argv)
 
void run ()
 
void sendDestJointMsg (thormang3_manipulation_module_msgs::JointPose msg)
 
void sendGripperPosition (sensor_msgs::JointState msg)
 
void sendIkMsg (thormang3_manipulation_module_msgs::KinematicsPose msg)
 
void sendInitPoseMsg (std_msgs::String msg)
 
bool setFeedBackGain ()
 
void setHeadJoint (double pan, double tilt)
 
void setWalkingBalance (bool on_command)
 
void setWalkingBalanceParam (const double &gyro_gain, const double &ft_gain_ratio, const double &imu_time_const, const double &ft_time_const)
 
void setWalkingCommand (thormang3_foot_step_generator::FootStepCommand msg)
 
void setWalkingFootsteps ()
 
void updateInteractiveMarker (const geometry_msgs::Pose &pose)
 
void visualizePreviewFootsteps (bool clear)
 
virtual ~QNodeThor3 ()
 

Public Attributes

std::map< int, std::string > module_table_
 
std::map< int, std::string > motion_table_
 
std::string package_name_
 

Private Types

enum  Control_Index {
  MODE_UI = 0, WALKING_UI = 1, MANIPULATION_UI = 2, HEAD_CONTROL_UI = 3,
  MOTION_UI = 4, DEMO_UI = 5
}
 

Private Member Functions

void initFTFootCallback (const thormang3_feet_ft_module_msgs::BothWrench::ConstPtr &msg)
 
void interactiveMarkerFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
bool loadBalanceParameterFromYaml ()
 
bool loadFeedbackGainFromYaml ()
 
void parseJointNameFromYaml (const std::string &path)
 
void parseMotionMapFromYaml (const std::string &path)
 
void pointStampedCallback (const geometry_msgs::PointStamped::ConstPtr &msg)
 
void poseCallback (const geometry_msgs::Pose::ConstPtr &msg)
 
void refreshCurrentJointControlCallback (const robotis_controller_msgs::JointCtrlModule::ConstPtr &msg)
 
void setBalanceParameter ()
 
void statusMsgCallback (const robotis_controller_msgs::StatusMsg::ConstPtr &msg)
 
void turnOffBalance ()
 
void turnOnBalance ()
 
void updateHeadJointStatesCallback (const sensor_msgs::JointState::ConstPtr &msg)
 

Private Attributes

ros::Subscriber both_ft_foot_sub_
 
int current_control_ui_
 
ros::Subscriber current_joint_states_sub_
 
ros::Subscriber current_module_control_sub_
 
geometry_msgs::Pose current_pose_
 
bool debug_print_
 
std::string frame_id_
 
ros::ServiceClient get_joint_pose_client_
 
ros::ServiceClient get_kinematics_pose_client_
 
ros::ServiceClient get_module_control_client_
 
ros::ServiceClient humanoid_footstep_client_
 
std::map< int, std::string > id_joint_table_
 
std::map< int, std::string > index_mode_table_
 
int init_argc_
 
char ** init_argv_
 
ros::Subscriber init_ft_foot_sub_
 
ros::Publisher init_ft_pub_
 
ros::Publisher init_pose_pub_
 
boost::shared_ptr< interactive_markers::InteractiveMarkerServerinteractive_marker_server_
 
std::map< std::string, int > joint_id_table_
 
ros::Subscriber kenematics_pose_sub_
 
QStringListModel logging_model_
 
std::string marker_name_
 
ros::Publisher marker_pub_
 
std::map< std::string, int > mode_index_table_
 
ros::Publisher module_control_preset_pub_
 
ros::Publisher module_control_pub_
 
ros::Publisher motion_index_pub_
 
ros::Publisher motion_page_pub_
 
ros::Publisher move_lidar_pub_
 
geometry_msgs::Pose pose_from_ui_
 
ros::Subscriber pose_sub_
 
std::vector< geometry_msgs::Pose2D > preview_foot_steps_
 
std::vector< int > preview_foot_types_
 
ros::Subscriber rviz_clicked_point_sub_
 
ros::Publisher send_des_joint_msg_pub_
 
ros::Publisher send_gripper_pub_
 
ros::Publisher send_ik_msg_pub_
 
ros::Publisher send_ini_pose_msg_pub_
 
ros::ServiceClient set_balance_param_client_
 
thormang3_walking_module_msgs::SetBalanceParam set_balance_param_srv_
 
ros::Publisher set_head_joint_angle_pub_
 
ros::ServiceClient set_joint_feedback_gain_client_
 
thormang3_walking_module_msgs::SetJointFeedBackGain set_joint_feedback_gain_srv_
 
ros::Publisher set_walking_balance_pub_
 
ros::Publisher set_walking_command_pub_
 
ros::Publisher set_walking_footsteps_pub_
 
ros::Time start_time_
 
ros::Subscriber status_msg_sub_
 
std::map< std::string, bool > using_mode_table_
 

Static Private Attributes

static const double DEGREE2RADIAN = M_PI / 180.0
 
static const double RADIAN2DEGREE = 180.0 / M_PI
 

Detailed Description

Definition at line 83 of file qnode.hpp.

Member Enumeration Documentation

Enumerator
MODE_UI 
WALKING_UI 
MANIPULATION_UI 
HEAD_CONTROL_UI 
MOTION_UI 
DEMO_UI 

Definition at line 193 of file qnode.hpp.

Enumerator
Debug 
Info 
Warn 
Error 
Fatal 

Definition at line 88 of file qnode.hpp.

Constructor & Destructor Documentation

thormang3_demo::QNodeThor3::QNodeThor3 ( int  argc,
char **  argv 
)

Definition at line 36 of file qnode.cpp.

thormang3_demo::QNodeThor3::~QNodeThor3 ( )
virtual

Definition at line 55 of file qnode.cpp.

Member Function Documentation

void thormang3_demo::QNodeThor3::assembleLidar ( )

Definition at line 386 of file qnode.cpp.

void thormang3_demo::QNodeThor3::clearFootsteps ( )

Definition at line 783 of file qnode.cpp.

void thormang3_demo::QNodeThor3::clearInteractiveMarker ( )

Definition at line 1487 of file qnode.cpp.

void thormang3_demo::QNodeThor3::clearLog ( )

Definition at line 1621 of file qnode.cpp.

void thormang3_demo::QNodeThor3::clearUsingModule ( )

Definition at line 342 of file qnode.cpp.

void thormang3_demo::QNodeThor3::enableControlModule ( const std::string &  mode)

Definition at line 396 of file qnode.cpp.

bool thormang3_demo::QNodeThor3::getIDFromJointName ( const std::string &  joint_name,
int &  id 
)

Definition at line 275 of file qnode.cpp.

bool thormang3_demo::QNodeThor3::getIDJointNameFromIndex ( const int &  index,
int &  id,
std::string &  joint_name 
)

Definition at line 288 of file qnode.cpp.

void thormang3_demo::QNodeThor3::getInteractiveMarkerPose ( )

Definition at line 1470 of file qnode.cpp.

void thormang3_demo::QNodeThor3::getJointControlModule ( )
slot

Definition at line 409 of file qnode.cpp.

bool thormang3_demo::QNodeThor3::getJointNameFromID ( const int &  id,
std::string &  joint_name 
)

Definition at line 262 of file qnode.cpp.

void thormang3_demo::QNodeThor3::getJointPose ( std::string  joint_name)
slot

Definition at line 604 of file qnode.cpp.

int thormang3_demo::QNodeThor3::getJointTableSize ( )

Definition at line 337 of file qnode.cpp.

void thormang3_demo::QNodeThor3::getKinematicsPose ( std::string  group_name)
slot

Definition at line 638 of file qnode.cpp.

void thormang3_demo::QNodeThor3::getKinematicsPoseCallback ( const geometry_msgs::Pose::ConstPtr &  msg)
slot

Definition at line 684 of file qnode.cpp.

int thormang3_demo::QNodeThor3::getModuleIndex ( const std::string &  mode_name)

Definition at line 319 of file qnode.cpp.

std::string thormang3_demo::QNodeThor3::getModuleName ( const int &  index)

Definition at line 307 of file qnode.cpp.

int thormang3_demo::QNodeThor3::getModuleTableSize ( )

Definition at line 331 of file qnode.cpp.

bool thormang3_demo::QNodeThor3::init ( )

Definition at line 66 of file qnode.cpp.

void thormang3_demo::QNodeThor3::initFTCommand ( std::string  command)

Definition at line 377 of file qnode.cpp.

void thormang3_demo::QNodeThor3::initFTFootCallback ( const thormang3_feet_ft_module_msgs::BothWrench::ConstPtr &  msg)
private

Definition at line 536 of file qnode.cpp.

void thormang3_demo::QNodeThor3::interactiveMarkerFeedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)
private

Definition at line 1276 of file qnode.cpp.

bool thormang3_demo::QNodeThor3::isUsingModule ( const std::string &  module_name)

Definition at line 349 of file qnode.cpp.

void thormang3_demo::QNodeThor3::kickDemo ( const std::string &  kick_foot)

Definition at line 1496 of file qnode.cpp.

bool thormang3_demo::QNodeThor3::loadBalanceParameterFromYaml ( )
private

Definition at line 988 of file qnode.cpp.

bool thormang3_demo::QNodeThor3::loadFeedbackGainFromYaml ( )
private

Definition at line 1110 of file qnode.cpp.

void thormang3_demo::QNodeThor3::log ( const LogLevel level,
const std::string &  msg,
std::string  sender = "Demo" 
)

Definition at line 1559 of file qnode.cpp.

QStringListModel* thormang3_demo::QNodeThor3::loggingModel ( )
inline

Definition at line 110 of file qnode.hpp.

void thormang3_demo::QNodeThor3::loggingUpdated ( )
signal
void thormang3_demo::QNodeThor3::makeFootstepUsingPlanner ( )

Definition at line 792 of file qnode.cpp.

void thormang3_demo::QNodeThor3::makeFootstepUsingPlanner ( const geometry_msgs::Pose target_foot_pose)

Definition at line 797 of file qnode.cpp.

void thormang3_demo::QNodeThor3::makeInteractiveMarker ( const geometry_msgs::Pose marker_pose)

Definition at line 1309 of file qnode.cpp.

void thormang3_demo::QNodeThor3::manipulationDemo ( const int &  index)
void thormang3_demo::QNodeThor3::moveInitPose ( )

Definition at line 367 of file qnode.cpp.

void thormang3_demo::QNodeThor3::parseJointNameFromYaml ( const std::string &  path)
private

Definition at line 173 of file qnode.cpp.

void thormang3_demo::QNodeThor3::parseMotionMapFromYaml ( const std::string &  path)
private

Definition at line 232 of file qnode.cpp.

void thormang3_demo::QNodeThor3::playMotion ( int  motion_index,
bool  to_action_script = true 
)

Definition at line 1204 of file qnode.cpp.

void thormang3_demo::QNodeThor3::pointStampedCallback ( const geometry_msgs::PointStamped::ConstPtr &  msg)
private

Definition at line 1266 of file qnode.cpp.

void thormang3_demo::QNodeThor3::poseCallback ( const geometry_msgs::Pose::ConstPtr &  msg)
private

Definition at line 1240 of file qnode.cpp.

void thormang3_demo::QNodeThor3::refreshCurrentJointControlCallback ( const robotis_controller_msgs::JointCtrlModule::ConstPtr &  msg)
private

Definition at line 464 of file qnode.cpp.

void thormang3_demo::QNodeThor3::rosShutdown ( )
signal
void thormang3_demo::QNodeThor3::run ( )

Definition at line 157 of file qnode.cpp.

void thormang3_demo::QNodeThor3::sendDestJointMsg ( thormang3_manipulation_module_msgs::JointPose  msg)

Definition at line 567 of file qnode.cpp.

void thormang3_demo::QNodeThor3::sendGripperPosition ( sensor_msgs::JointState  msg)

Definition at line 598 of file qnode.cpp.

void thormang3_demo::QNodeThor3::sendIkMsg ( thormang3_manipulation_module_msgs::KinematicsPose  msg)

Definition at line 580 of file qnode.cpp.

void thormang3_demo::QNodeThor3::sendInitPoseMsg ( std_msgs::String  msg)

Definition at line 560 of file qnode.cpp.

void thormang3_demo::QNodeThor3::setBalanceParameter ( )
private

Definition at line 959 of file qnode.cpp.

void thormang3_demo::QNodeThor3::setCurrentControlUI ( int  mode)
slot

Definition at line 359 of file qnode.cpp.

bool thormang3_demo::QNodeThor3::setFeedBackGain ( )

Definition at line 1073 of file qnode.cpp.

void thormang3_demo::QNodeThor3::setHeadJoint ( double  pan,
double  tilt 
)

Definition at line 546 of file qnode.cpp.

void thormang3_demo::QNodeThor3::setWalkingBalance ( bool  on_command)

Definition at line 706 of file qnode.cpp.

void thormang3_demo::QNodeThor3::setWalkingBalanceParam ( const double &  gyro_gain,
const double &  ft_gain_ratio,
const double &  imu_time_const,
const double &  ft_time_const 
)

Definition at line 714 of file qnode.cpp.

void thormang3_demo::QNodeThor3::setWalkingCommand ( thormang3_foot_step_generator::FootStepCommand  msg)

Definition at line 692 of file qnode.cpp.

void thormang3_demo::QNodeThor3::setWalkingFootsteps ( )

Definition at line 744 of file qnode.cpp.

void thormang3_demo::QNodeThor3::statusMsgCallback ( const robotis_controller_msgs::StatusMsg::ConstPtr &  msg)
private

Definition at line 1554 of file qnode.cpp.

void thormang3_demo::QNodeThor3::turnOffBalance ( )
private

Definition at line 1170 of file qnode.cpp.

void thormang3_demo::QNodeThor3::turnOnBalance ( )
private

Definition at line 1157 of file qnode.cpp.

void thormang3_demo::QNodeThor3::updateCurrJoint ( double  value)
signal
void thormang3_demo::QNodeThor3::updateCurrOri ( double  x,
double  y,
double  z,
double  w 
)
signal
void thormang3_demo::QNodeThor3::updateCurrPos ( double  x,
double  y,
double  z 
)
signal
void thormang3_demo::QNodeThor3::updateDemoPoint ( const geometry_msgs::Point  point)
signal
void thormang3_demo::QNodeThor3::updateDemoPose ( const geometry_msgs::Pose  pose)
signal
void thormang3_demo::QNodeThor3::updateHeadJointsAngle ( double  pan,
double  tilt 
)
signal
void thormang3_demo::QNodeThor3::updateHeadJointStatesCallback ( const sensor_msgs::JointState::ConstPtr &  msg)
private

Definition at line 510 of file qnode.cpp.

void thormang3_demo::QNodeThor3::updateInteractiveMarker ( const geometry_msgs::Pose pose)

Definition at line 1452 of file qnode.cpp.

void thormang3_demo::QNodeThor3::updatePresentJointControlModules ( std::vector< int >  mode)
signal
void thormang3_demo::QNodeThor3::visualizePreviewFootsteps ( bool  clear)

Definition at line 869 of file qnode.cpp.

Member Data Documentation

ros::Subscriber thormang3_demo::QNodeThor3::both_ft_foot_sub_
private

Definition at line 244 of file qnode.hpp.

int thormang3_demo::QNodeThor3::current_control_ui_
private

Definition at line 226 of file qnode.hpp.

ros::Subscriber thormang3_demo::QNodeThor3::current_joint_states_sub_
private

Definition at line 254 of file qnode.hpp.

ros::Subscriber thormang3_demo::QNodeThor3::current_module_control_sub_
private

Definition at line 245 of file qnode.hpp.

geometry_msgs::Pose thormang3_demo::QNodeThor3::current_pose_
private

Definition at line 233 of file qnode.hpp.

bool thormang3_demo::QNodeThor3::debug_print_
private

Definition at line 225 of file qnode.hpp.

const double thormang3_demo::QNodeThor3::DEGREE2RADIAN = M_PI / 180.0
staticprivate

Definition at line 203 of file qnode.hpp.

std::string thormang3_demo::QNodeThor3::frame_id_
private

Definition at line 230 of file qnode.hpp.

ros::ServiceClient thormang3_demo::QNodeThor3::get_joint_pose_client_
private

Definition at line 261 of file qnode.hpp.

ros::ServiceClient thormang3_demo::QNodeThor3::get_kinematics_pose_client_
private

Definition at line 262 of file qnode.hpp.

ros::ServiceClient thormang3_demo::QNodeThor3::get_module_control_client_
private

Definition at line 246 of file qnode.hpp.

ros::ServiceClient thormang3_demo::QNodeThor3::humanoid_footstep_client_
private

Definition at line 267 of file qnode.hpp.

std::map<int, std::string> thormang3_demo::QNodeThor3::id_joint_table_
private

Definition at line 283 of file qnode.hpp.

std::map<int, std::string> thormang3_demo::QNodeThor3::index_mode_table_
private

Definition at line 285 of file qnode.hpp.

int thormang3_demo::QNodeThor3::init_argc_
private

Definition at line 223 of file qnode.hpp.

char** thormang3_demo::QNodeThor3::init_argv_
private

Definition at line 224 of file qnode.hpp.

ros::Subscriber thormang3_demo::QNodeThor3::init_ft_foot_sub_
private

Definition at line 243 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::init_ft_pub_
private

Definition at line 239 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::init_pose_pub_
private

Definition at line 238 of file qnode.hpp.

boost::shared_ptr<interactive_markers::InteractiveMarkerServer> thormang3_demo::QNodeThor3::interactive_marker_server_
private

Definition at line 234 of file qnode.hpp.

std::map<std::string, int> thormang3_demo::QNodeThor3::joint_id_table_
private

Definition at line 284 of file qnode.hpp.

ros::Subscriber thormang3_demo::QNodeThor3::kenematics_pose_sub_
private

Definition at line 260 of file qnode.hpp.

QStringListModel thormang3_demo::QNodeThor3::logging_model_
private

Definition at line 282 of file qnode.hpp.

std::string thormang3_demo::QNodeThor3::marker_name_
private

Definition at line 231 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::marker_pub_
private

Definition at line 248 of file qnode.hpp.

std::map<std::string, int> thormang3_demo::QNodeThor3::mode_index_table_
private

Definition at line 286 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::module_control_preset_pub_
private

Definition at line 241 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::module_control_pub_
private

Definition at line 240 of file qnode.hpp.

std::map<int, std::string> thormang3_demo::QNodeThor3::module_table_

Definition at line 163 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::motion_index_pub_
private

Definition at line 278 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::motion_page_pub_
private

Definition at line 279 of file qnode.hpp.

std::map<int, std::string> thormang3_demo::QNodeThor3::motion_table_

Definition at line 164 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::move_lidar_pub_
private

Definition at line 252 of file qnode.hpp.

std::string thormang3_demo::QNodeThor3::package_name_

Definition at line 166 of file qnode.hpp.

geometry_msgs::Pose thormang3_demo::QNodeThor3::pose_from_ui_
private

Definition at line 232 of file qnode.hpp.

ros::Subscriber thormang3_demo::QNodeThor3::pose_sub_
private

Definition at line 249 of file qnode.hpp.

std::vector<geometry_msgs::Pose2D> thormang3_demo::QNodeThor3::preview_foot_steps_
private

Definition at line 274 of file qnode.hpp.

std::vector<int> thormang3_demo::QNodeThor3::preview_foot_types_
private

Definition at line 275 of file qnode.hpp.

const double thormang3_demo::QNodeThor3::RADIAN2DEGREE = 180.0 / M_PI
staticprivate

Definition at line 204 of file qnode.hpp.

ros::Subscriber thormang3_demo::QNodeThor3::rviz_clicked_point_sub_
private

Definition at line 229 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::send_des_joint_msg_pub_
private

Definition at line 258 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::send_gripper_pub_
private

Definition at line 264 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::send_ik_msg_pub_
private

Definition at line 259 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::send_ini_pose_msg_pub_
private

Definition at line 257 of file qnode.hpp.

ros::ServiceClient thormang3_demo::QNodeThor3::set_balance_param_client_
private

Definition at line 268 of file qnode.hpp.

thormang3_walking_module_msgs::SetBalanceParam thormang3_demo::QNodeThor3::set_balance_param_srv_
private

Definition at line 235 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::set_head_joint_angle_pub_
private

Definition at line 253 of file qnode.hpp.

ros::ServiceClient thormang3_demo::QNodeThor3::set_joint_feedback_gain_client_
private

Definition at line 269 of file qnode.hpp.

thormang3_walking_module_msgs::SetJointFeedBackGain thormang3_demo::QNodeThor3::set_joint_feedback_gain_srv_
private

Definition at line 236 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::set_walking_balance_pub_
private

Definition at line 272 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::set_walking_command_pub_
private

Definition at line 270 of file qnode.hpp.

ros::Publisher thormang3_demo::QNodeThor3::set_walking_footsteps_pub_
private

Definition at line 271 of file qnode.hpp.

ros::Time thormang3_demo::QNodeThor3::start_time_
private

Definition at line 281 of file qnode.hpp.

ros::Subscriber thormang3_demo::QNodeThor3::status_msg_sub_
private

Definition at line 242 of file qnode.hpp.

std::map<std::string, bool> thormang3_demo::QNodeThor3::using_mode_table_
private

Definition at line 287 of file qnode.hpp.


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


thormang3_demo
Author(s): Kayman
autogenerated on Mon Jun 10 2019 15:38:34