Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_footstep_controller::Footcoords Class Reference

#include <footcoords.h>

Public Types

typedef message_filters::sync_policies::ExactTime< nav_msgs::Odometry, sensor_msgs::Imu > OdomImuSyncPolicy
 
enum  OdomStatus { UNINITIALIZED, INITIALIZING, LLEG_SUPPORT, RLEG_SUPPORT }
 
enum  SupportLegStatus { LLEG_GROUND, RLEG_GROUND, AIR, BOTH_GROUND }
 
typedef message_filters::sync_policies::ExactTime< geometry_msgs::WrenchStamped, geometry_msgs::WrenchStamped, sensor_msgs::JointState, geometry_msgs::PointStamped > SyncPolicy
 

Public Member Functions

 Footcoords ()
 
virtual ~Footcoords ()
 

Protected Member Functions

virtual bool allValueLargerThan (TimeStampedVector< ValueStamped::Ptr > &values, double threshold)
 
virtual bool allValueSmallerThan (TimeStampedVector< ValueStamped::Ptr > &values, double threshold)
 
virtual double applyLowPassFilter (double current_val, double prev_val) const
 
virtual bool computeMidCoords (const ros::Time &stamp)
 
virtual bool computeMidCoordsFromSingleLeg (const ros::Time &stamp, bool use_left_leg)
 
virtual void computeVelicity (double dt, std::map< std::string, double > &joint_angles, KDL::Chain &chain, geometry_msgs::Twist &output)
 
virtual void estimateOdometry ()
 
virtual void estimateOdometryMainSupportLeg ()
 
virtual void estimateOdometryNaive ()
 
virtual void estimateOdometryZMPSupportLeg ()
 
virtual void estimateVelocity (const ros::Time &stamp, std::map< std::string, double > &joint_angles)
 
virtual void filter (const jsk_footstep_controller::SynchronizedForces::ConstPtr &msg)
 
virtual void floorCoeffsCallback (const pcl_msgs::ModelCoefficients &coeffs)
 
virtual void getRollPitch (const Eigen::Affine3d &pose, float &roll, float &pitch)
 
virtual float getYaw (const Eigen::Affine3d &pose)
 
virtual void odomImuCallback (const nav_msgs::Odometry::ConstPtr &odom_msg, const sensor_msgs::Imu::ConstPtr &imu_msg)
 
virtual void odomInitTriggerCallback (const std_msgs::Empty &trigger)
 
virtual void periodicTimerCallback (const ros::TimerEvent &event)
 
virtual void publishContactState (const ros::Time &stamp)
 
virtual void publishState (const std::string &state)
 
virtual void publishTF (const ros::Time &stamp)
 
virtual bool resolveForceTf (const geometry_msgs::WrenchStamped &lfoot, const geometry_msgs::WrenchStamped &rfoot, tf::Vector3 &lfoot_force, tf::Vector3 &rfoot_force)
 
virtual void synchronizeForces (const geometry_msgs::WrenchStamped::ConstPtr &lfoot, const geometry_msgs::WrenchStamped::ConstPtr &rfoot, const sensor_msgs::JointState::ConstPtr &joint_states, const geometry_msgs::PointStamped::ConstPtr &zmp)
 
virtual void updateChain (std::map< std::string, double > &joint_angles, KDL::Chain &chain, tf::Pose &output_pose)
 
virtual bool updateGroundTF ()
 
virtual void updateLegDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
virtual void updateRobotModel (std::map< std::string, double > &joint_angles)
 
virtual bool waitForEndEffectorTransformation (const ros::Time &stamp)
 
virtual bool waitForSensorFrameTransformation (const ros::Time &lstamp, const ros::Time &rstamp, const std::string &lsensor_frame, const std::string &rsensor_frame)
 

Protected Attributes

double alpha_
 
bool before_on_the_air_
 
std::string body_on_odom_frame_
 
boost::shared_ptr< diagnostic_updater::Updaterdiagnostic_updater_
 
tf::Pose estimated_odom_pose_
 
std::vector< floatfloor_coeffs_
 
ros::Subscriber floor_coeffs_sub_
 
double force_thr_
 
tf::Transform ground_transform_
 
message_filters::Subscriber< sensor_msgs::Imu > imu_sub_
 
bool invert_odom_init_
 
ros::Time last_time_
 
KDL::Chain lfoot_chain_
 
std::string lfoot_frame_id_
 
tf::Pose lfoot_pose_
 
std::string lfoot_sensor_frame_
 
tf::Pose lfoot_to_origin_pose_
 
tf::Transform locked_midcoords_to_odom_on_ground_
 
tf::Transform midcoords_
 
std::string midcoords_frame_id_
 
boost::mutex mutex_
 
boost::shared_ptr< message_filters::Synchronizer< OdomImuSyncPolicy > > odom_imu_sync_
 
std::string odom_init_frame_id_
 
Eigen::Affine3d odom_init_pose_
 
ros::Subscriber odom_init_trigger_sub_
 
Eigen::Affine3d odom_pose_
 
OdomStatus odom_status_
 
message_filters::Subscriber< nav_msgs::Odometry > odom_sub_
 
std::string output_frame_id_
 
std::string parent_frame_id_
 
ros::Timer periodic_update_timer_
 
std::map< std::string, double > prev_joints_
 
double prev_lforce_
 
double prev_rforce_
 
ros::Publisher pub_contact_state_
 
ros::Publisher pub_debug_lfoot_pos_
 
ros::Publisher pub_debug_rfoot_pos_
 
ros::Publisher pub_leg_odometory_
 
ros::Publisher pub_low_level_
 
ros::Publisher pub_odom_init_pose_stamped_
 
ros::Publisher pub_odom_init_transform_
 
ros::Publisher pub_state_
 
ros::Publisher pub_synchronized_forces_
 
ros::Publisher pub_twist_
 
bool publish_odom_tf_
 
KDL::Chain rfoot_chain_
 
std::string rfoot_frame_id_
 
tf::Pose rfoot_pose_
 
std::string rfoot_sensor_frame_
 
tf::Pose rfoot_to_origin_pose_
 
std::string root_frame_id_
 
tf::Transform root_link_pose_
 
double sampling_time_
 
message_filters::Subscriber< sensor_msgs::JointState > sub_joint_states_
 
message_filters::Subscriber< geometry_msgs::WrenchStamped > sub_lfoot_force_
 
message_filters::Subscriber< geometry_msgs::WrenchStamped > sub_rfoot_force_
 
message_filters::Subscriber< geometry_msgs::PointStamped > sub_zmp_
 
SupportLegStatus support_status_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 
ros::Subscriber synchronized_forces_sub_
 
tf::TransformBroadcaster tf_broadcaster_
 
boost::shared_ptr< tf::TransformListenertf_listener_
 
bool use_imu_
 
bool use_imu_yaw_
 
Eigen::Vector3f zmp_
 
std::string zmp_frame_id_
 

Detailed Description

Definition at line 129 of file footcoords.h.

Member Typedef Documentation

◆ OdomImuSyncPolicy

Definition at line 139 of file footcoords.h.

◆ SyncPolicy

typedef message_filters::sync_policies::ExactTime< geometry_msgs::WrenchStamped, geometry_msgs::WrenchStamped, sensor_msgs::JointState, geometry_msgs::PointStamped> jsk_footstep_controller::Footcoords::SyncPolicy

Definition at line 136 of file footcoords.h.

Member Enumeration Documentation

◆ OdomStatus

Enumerator
UNINITIALIZED 
INITIALIZING 
LLEG_SUPPORT 
RLEG_SUPPORT 

Definition at line 149 of file footcoords.h.

◆ SupportLegStatus

Enumerator
LLEG_GROUND 
RLEG_GROUND 
AIR 
BOTH_GROUND 

Definition at line 144 of file footcoords.h.

Constructor & Destructor Documentation

◆ Footcoords()

jsk_footstep_controller::Footcoords::Footcoords ( )

Definition at line 83 of file footcoords.cpp.

◆ ~Footcoords()

jsk_footstep_controller::Footcoords::~Footcoords ( )
virtual

Definition at line 183 of file footcoords.cpp.

Member Function Documentation

◆ allValueLargerThan()

bool jsk_footstep_controller::Footcoords::allValueLargerThan ( TimeStampedVector< ValueStamped::Ptr > &  values,
double  threshold 
)
protectedvirtual

Definition at line 213 of file footcoords.cpp.

◆ allValueSmallerThan()

bool jsk_footstep_controller::Footcoords::allValueSmallerThan ( TimeStampedVector< ValueStamped::Ptr > &  values,
double  threshold 
)
protectedvirtual

Definition at line 224 of file footcoords.cpp.

◆ applyLowPassFilter()

double jsk_footstep_controller::Footcoords::applyLowPassFilter ( double  current_val,
double  prev_val 
) const
protectedvirtual

Definition at line 208 of file footcoords.cpp.

◆ computeMidCoords()

bool jsk_footstep_controller::Footcoords::computeMidCoords ( const ros::Time stamp)
protectedvirtual

Definition at line 838 of file footcoords.cpp.

◆ computeMidCoordsFromSingleLeg()

bool jsk_footstep_controller::Footcoords::computeMidCoordsFromSingleLeg ( const ros::Time stamp,
bool  use_left_leg 
)
protectedvirtual

Definition at line 793 of file footcoords.cpp.

◆ computeVelicity()

void jsk_footstep_controller::Footcoords::computeVelicity ( double  dt,
std::map< std::string, double > &  joint_angles,
KDL::Chain &  chain,
geometry_msgs::Twist &  output 
)
protectedvirtual

Definition at line 395 of file footcoords.cpp.

◆ estimateOdometry()

void jsk_footstep_controller::Footcoords::estimateOdometry ( )
protectedvirtual

Definition at line 506 of file footcoords.cpp.

◆ estimateOdometryMainSupportLeg()

void jsk_footstep_controller::Footcoords::estimateOdometryMainSupportLeg ( )
protectedvirtual

Definition at line 574 of file footcoords.cpp.

◆ estimateOdometryNaive()

void jsk_footstep_controller::Footcoords::estimateOdometryNaive ( )
protectedvirtual

Definition at line 512 of file footcoords.cpp.

◆ estimateOdometryZMPSupportLeg()

void jsk_footstep_controller::Footcoords::estimateOdometryZMPSupportLeg ( )
protectedvirtual

Definition at line 653 of file footcoords.cpp.

◆ estimateVelocity()

void jsk_footstep_controller::Footcoords::estimateVelocity ( const ros::Time stamp,
std::map< std::string, double > &  joint_angles 
)
protectedvirtual

Definition at line 420 of file footcoords.cpp.

◆ filter()

void jsk_footstep_controller::Footcoords::filter ( const jsk_footstep_controller::SynchronizedForces::ConstPtr &  msg)
protectedvirtual

Definition at line 437 of file footcoords.cpp.

◆ floorCoeffsCallback()

void jsk_footstep_controller::Footcoords::floorCoeffsCallback ( const pcl_msgs::ModelCoefficients &  coeffs)
protectedvirtual

Definition at line 1083 of file footcoords.cpp.

◆ getRollPitch()

void jsk_footstep_controller::Footcoords::getRollPitch ( const Eigen::Affine3d &  pose,
float roll,
float pitch 
)
protectedvirtual

Definition at line 969 of file footcoords.cpp.

◆ getYaw()

float jsk_footstep_controller::Footcoords::getYaw ( const Eigen::Affine3d &  pose)
protectedvirtual

Definition at line 977 of file footcoords.cpp.

◆ odomImuCallback()

void jsk_footstep_controller::Footcoords::odomImuCallback ( const nav_msgs::Odometry::ConstPtr &  odom_msg,
const sensor_msgs::Imu::ConstPtr &  imu_msg 
)
protectedvirtual

Definition at line 1115 of file footcoords.cpp.

◆ odomInitTriggerCallback()

void jsk_footstep_controller::Footcoords::odomInitTriggerCallback ( const std_msgs::Empty &  trigger)
protectedvirtual

Definition at line 1053 of file footcoords.cpp.

◆ periodicTimerCallback()

void jsk_footstep_controller::Footcoords::periodicTimerCallback ( const ros::TimerEvent event)
protectedvirtual

Definition at line 281 of file footcoords.cpp.

◆ publishContactState()

void jsk_footstep_controller::Footcoords::publishContactState ( const ros::Time stamp)
protectedvirtual

Definition at line 741 of file footcoords.cpp.

◆ publishState()

void jsk_footstep_controller::Footcoords::publishState ( const std::string state)
protectedvirtual

Definition at line 734 of file footcoords.cpp.

◆ publishTF()

void jsk_footstep_controller::Footcoords::publishTF ( const ros::Time stamp)
protectedvirtual

Definition at line 986 of file footcoords.cpp.

◆ resolveForceTf()

bool jsk_footstep_controller::Footcoords::resolveForceTf ( const geometry_msgs::WrenchStamped &  lfoot,
const geometry_msgs::WrenchStamped &  rfoot,
tf::Vector3 lfoot_force,
tf::Vector3 rfoot_force 
)
protectedvirtual

Definition at line 235 of file footcoords.cpp.

◆ synchronizeForces()

void jsk_footstep_controller::Footcoords::synchronizeForces ( const geometry_msgs::WrenchStamped::ConstPtr &  lfoot,
const geometry_msgs::WrenchStamped::ConstPtr &  rfoot,
const sensor_msgs::JointState::ConstPtr &  joint_states,
const geometry_msgs::PointStamped::ConstPtr &  zmp 
)
protectedvirtual

Definition at line 330 of file footcoords.cpp.

◆ updateChain()

void jsk_footstep_controller::Footcoords::updateChain ( std::map< std::string, double > &  joint_angles,
KDL::Chain &  chain,
tf::Pose output_pose 
)
protectedvirtual

Definition at line 360 of file footcoords.cpp.

◆ updateGroundTF()

bool jsk_footstep_controller::Footcoords::updateGroundTF ( )
protectedvirtual

Definition at line 938 of file footcoords.cpp.

◆ updateLegDiagnostics()

void jsk_footstep_controller::Footcoords::updateLegDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)
protectedvirtual

Definition at line 188 of file footcoords.cpp.

◆ updateRobotModel()

void jsk_footstep_controller::Footcoords::updateRobotModel ( std::map< std::string, double > &  joint_angles)
protectedvirtual

Definition at line 383 of file footcoords.cpp.

◆ waitForEndEffectorTransformation()

bool jsk_footstep_controller::Footcoords::waitForEndEffectorTransformation ( const ros::Time stamp)
protectedvirtual

Definition at line 909 of file footcoords.cpp.

◆ waitForSensorFrameTransformation()

bool jsk_footstep_controller::Footcoords::waitForSensorFrameTransformation ( const ros::Time lstamp,
const ros::Time rstamp,
const std::string lsensor_frame,
const std::string rsensor_frame 
)
protectedvirtual

Definition at line 886 of file footcoords.cpp.

Member Data Documentation

◆ alpha_

double jsk_footstep_controller::Footcoords::alpha_
protected

Definition at line 276 of file footcoords.h.

◆ before_on_the_air_

bool jsk_footstep_controller::Footcoords::before_on_the_air_
protected

Definition at line 256 of file footcoords.h.

◆ body_on_odom_frame_

std::string jsk_footstep_controller::Footcoords::body_on_odom_frame_
protected

Definition at line 266 of file footcoords.h.

◆ diagnostic_updater_

boost::shared_ptr<diagnostic_updater::Updater> jsk_footstep_controller::Footcoords::diagnostic_updater_
protected

Definition at line 273 of file footcoords.h.

◆ estimated_odom_pose_

tf::Pose jsk_footstep_controller::Footcoords::estimated_odom_pose_
protected

Definition at line 234 of file footcoords.h.

◆ floor_coeffs_

std::vector<float> jsk_footstep_controller::Footcoords::floor_coeffs_
protected

Definition at line 227 of file footcoords.h.

◆ floor_coeffs_sub_

ros::Subscriber jsk_footstep_controller::Footcoords::floor_coeffs_sub_
protected

Definition at line 226 of file footcoords.h.

◆ force_thr_

double jsk_footstep_controller::Footcoords::force_thr_
protected

Definition at line 255 of file footcoords.h.

◆ ground_transform_

tf::Transform jsk_footstep_controller::Footcoords::ground_transform_
protected

Definition at line 269 of file footcoords.h.

◆ imu_sub_

message_filters::Subscriber<sensor_msgs::Imu> jsk_footstep_controller::Footcoords::imu_sub_
protected

Definition at line 218 of file footcoords.h.

◆ invert_odom_init_

bool jsk_footstep_controller::Footcoords::invert_odom_init_
protected

Definition at line 268 of file footcoords.h.

◆ last_time_

ros::Time jsk_footstep_controller::Footcoords::last_time_
protected

Definition at line 260 of file footcoords.h.

◆ lfoot_chain_

KDL::Chain jsk_footstep_controller::Footcoords::lfoot_chain_
protected

Definition at line 228 of file footcoords.h.

◆ lfoot_frame_id_

std::string jsk_footstep_controller::Footcoords::lfoot_frame_id_
protected

Definition at line 261 of file footcoords.h.

◆ lfoot_pose_

tf::Pose jsk_footstep_controller::Footcoords::lfoot_pose_
protected

Definition at line 230 of file footcoords.h.

◆ lfoot_sensor_frame_

std::string jsk_footstep_controller::Footcoords::lfoot_sensor_frame_
protected

Definition at line 263 of file footcoords.h.

◆ lfoot_to_origin_pose_

tf::Pose jsk_footstep_controller::Footcoords::lfoot_to_origin_pose_
protected

Definition at line 232 of file footcoords.h.

◆ locked_midcoords_to_odom_on_ground_

tf::Transform jsk_footstep_controller::Footcoords::locked_midcoords_to_odom_on_ground_
protected

Definition at line 272 of file footcoords.h.

◆ midcoords_

tf::Transform jsk_footstep_controller::Footcoords::midcoords_
protected

Definition at line 270 of file footcoords.h.

◆ midcoords_frame_id_

std::string jsk_footstep_controller::Footcoords::midcoords_frame_id_
protected

Definition at line 251 of file footcoords.h.

◆ mutex_

boost::mutex jsk_footstep_controller::Footcoords::mutex_
protected

Definition at line 211 of file footcoords.h.

◆ odom_imu_sync_

boost::shared_ptr<message_filters::Synchronizer<OdomImuSyncPolicy> > jsk_footstep_controller::Footcoords::odom_imu_sync_
protected

Definition at line 219 of file footcoords.h.

◆ odom_init_frame_id_

std::string jsk_footstep_controller::Footcoords::odom_init_frame_id_
protected

Definition at line 267 of file footcoords.h.

◆ odom_init_pose_

Eigen::Affine3d jsk_footstep_controller::Footcoords::odom_init_pose_
protected

Definition at line 213 of file footcoords.h.

◆ odom_init_trigger_sub_

ros::Subscriber jsk_footstep_controller::Footcoords::odom_init_trigger_sub_
protected

Definition at line 215 of file footcoords.h.

◆ odom_pose_

Eigen::Affine3d jsk_footstep_controller::Footcoords::odom_pose_
protected

Definition at line 212 of file footcoords.h.

◆ odom_status_

OdomStatus jsk_footstep_controller::Footcoords::odom_status_
protected

Definition at line 253 of file footcoords.h.

◆ odom_sub_

message_filters::Subscriber<nav_msgs::Odometry> jsk_footstep_controller::Footcoords::odom_sub_
protected

Definition at line 217 of file footcoords.h.

◆ output_frame_id_

std::string jsk_footstep_controller::Footcoords::output_frame_id_
protected

Definition at line 249 of file footcoords.h.

◆ parent_frame_id_

std::string jsk_footstep_controller::Footcoords::parent_frame_id_
protected

Definition at line 250 of file footcoords.h.

◆ periodic_update_timer_

ros::Timer jsk_footstep_controller::Footcoords::periodic_update_timer_
protected

Definition at line 214 of file footcoords.h.

◆ prev_joints_

std::map<std::string, double> jsk_footstep_controller::Footcoords::prev_joints_
protected

Definition at line 257 of file footcoords.h.

◆ prev_lforce_

double jsk_footstep_controller::Footcoords::prev_lforce_
protected

Definition at line 274 of file footcoords.h.

◆ prev_rforce_

double jsk_footstep_controller::Footcoords::prev_rforce_
protected

Definition at line 275 of file footcoords.h.

◆ pub_contact_state_

ros::Publisher jsk_footstep_controller::Footcoords::pub_contact_state_
protected

Definition at line 236 of file footcoords.h.

◆ pub_debug_lfoot_pos_

ros::Publisher jsk_footstep_controller::Footcoords::pub_debug_lfoot_pos_
protected

Definition at line 239 of file footcoords.h.

◆ pub_debug_rfoot_pos_

ros::Publisher jsk_footstep_controller::Footcoords::pub_debug_rfoot_pos_
protected

Definition at line 240 of file footcoords.h.

◆ pub_leg_odometory_

ros::Publisher jsk_footstep_controller::Footcoords::pub_leg_odometory_
protected

Definition at line 241 of file footcoords.h.

◆ pub_low_level_

ros::Publisher jsk_footstep_controller::Footcoords::pub_low_level_
protected

Definition at line 237 of file footcoords.h.

◆ pub_odom_init_pose_stamped_

ros::Publisher jsk_footstep_controller::Footcoords::pub_odom_init_pose_stamped_
protected

Definition at line 244 of file footcoords.h.

◆ pub_odom_init_transform_

ros::Publisher jsk_footstep_controller::Footcoords::pub_odom_init_transform_
protected

Definition at line 243 of file footcoords.h.

◆ pub_state_

ros::Publisher jsk_footstep_controller::Footcoords::pub_state_
protected

Definition at line 235 of file footcoords.h.

◆ pub_synchronized_forces_

ros::Publisher jsk_footstep_controller::Footcoords::pub_synchronized_forces_
protected

Definition at line 238 of file footcoords.h.

◆ pub_twist_

ros::Publisher jsk_footstep_controller::Footcoords::pub_twist_
protected

Definition at line 242 of file footcoords.h.

◆ publish_odom_tf_

bool jsk_footstep_controller::Footcoords::publish_odom_tf_
protected

Definition at line 278 of file footcoords.h.

◆ rfoot_chain_

KDL::Chain jsk_footstep_controller::Footcoords::rfoot_chain_
protected

Definition at line 229 of file footcoords.h.

◆ rfoot_frame_id_

std::string jsk_footstep_controller::Footcoords::rfoot_frame_id_
protected

Definition at line 262 of file footcoords.h.

◆ rfoot_pose_

tf::Pose jsk_footstep_controller::Footcoords::rfoot_pose_
protected

Definition at line 231 of file footcoords.h.

◆ rfoot_sensor_frame_

std::string jsk_footstep_controller::Footcoords::rfoot_sensor_frame_
protected

Definition at line 264 of file footcoords.h.

◆ rfoot_to_origin_pose_

tf::Pose jsk_footstep_controller::Footcoords::rfoot_to_origin_pose_
protected

Definition at line 233 of file footcoords.h.

◆ root_frame_id_

std::string jsk_footstep_controller::Footcoords::root_frame_id_
protected

Definition at line 265 of file footcoords.h.

◆ root_link_pose_

tf::Transform jsk_footstep_controller::Footcoords::root_link_pose_
protected

Definition at line 271 of file footcoords.h.

◆ sampling_time_

double jsk_footstep_controller::Footcoords::sampling_time_
protected

Definition at line 277 of file footcoords.h.

◆ sub_joint_states_

message_filters::Subscriber<sensor_msgs::JointState> jsk_footstep_controller::Footcoords::sub_joint_states_
protected

Definition at line 223 of file footcoords.h.

◆ sub_lfoot_force_

message_filters::Subscriber<geometry_msgs::WrenchStamped> jsk_footstep_controller::Footcoords::sub_lfoot_force_
protected

Definition at line 221 of file footcoords.h.

◆ sub_rfoot_force_

message_filters::Subscriber<geometry_msgs::WrenchStamped> jsk_footstep_controller::Footcoords::sub_rfoot_force_
protected

Definition at line 222 of file footcoords.h.

◆ sub_zmp_

message_filters::Subscriber<geometry_msgs::PointStamped> jsk_footstep_controller::Footcoords::sub_zmp_
protected

Definition at line 224 of file footcoords.h.

◆ support_status_

SupportLegStatus jsk_footstep_controller::Footcoords::support_status_
protected

Definition at line 252 of file footcoords.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_footstep_controller::Footcoords::sync_
protected

Definition at line 225 of file footcoords.h.

◆ synchronized_forces_sub_

ros::Subscriber jsk_footstep_controller::Footcoords::synchronized_forces_sub_
protected

Definition at line 220 of file footcoords.h.

◆ tf_broadcaster_

tf::TransformBroadcaster jsk_footstep_controller::Footcoords::tf_broadcaster_
protected

Definition at line 246 of file footcoords.h.

◆ tf_listener_

boost::shared_ptr<tf::TransformListener> jsk_footstep_controller::Footcoords::tf_listener_
protected

Definition at line 245 of file footcoords.h.

◆ use_imu_

bool jsk_footstep_controller::Footcoords::use_imu_
protected

Definition at line 258 of file footcoords.h.

◆ use_imu_yaw_

bool jsk_footstep_controller::Footcoords::use_imu_yaw_
protected

Definition at line 259 of file footcoords.h.

◆ zmp_

Eigen::Vector3f jsk_footstep_controller::Footcoords::zmp_
protected

Definition at line 254 of file footcoords.h.

◆ zmp_frame_id_

std::string jsk_footstep_controller::Footcoords::zmp_frame_id_
protected

Definition at line 248 of file footcoords.h.


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


jsk_footstep_controller
Author(s):
autogenerated on Mon Dec 9 2024 04:11:17