footcoords.h
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Ryohei Ueda and JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef JSK_FOOTSTEP_CONTROLLER_FOOTCOORDS_H_
37 #define JSK_FOOTSTEP_CONTROLLER_FOOTCOORDS_H_
38 #include <Eigen/Geometry>
39 #include <sensor_msgs/Imu.h>
40 #include <geometry_msgs/WrenchStamped.h>
41 #include <tf/transform_listener.h>
47 #include <tf/transform_listener.h>
50 #include <pcl_msgs/ModelCoefficients.h>
51 #include <jsk_footstep_controller/GroundContactState.h>
52 #include <jsk_footstep_controller/FootCoordsLowLevelInfo.h>
53 #include <jsk_footstep_controller/SynchronizedForces.h>
54 #include <std_msgs/Empty.h>
55 #include <nav_msgs/Odometry.h>
56 #include <urdf/model.h>
57 #include <kdl/tree.hpp>
58 #include <kdl/chainjnttojacsolver.hpp>
60 
62 {
63  template <class T>
64  class TimeStampedVector: public std::vector<T>
65  {
66  public:
67  typedef typename std::vector<T>::iterator iterator;
68  void removeBefore(const ros::Time& stamp)
69  {
70  for (iterator it = std::vector<T>::begin();
71  it != std::vector<T>::end();) {
72  if (((*it)->header.stamp - stamp) < ros::Duration(0.0)) {
73  it = this->erase(it);
74  }
75  else {
76  ++it;
77  }
78  }
79  }
80  protected:
81  private:
82  };
83 
84 
85  class ValueStamped
86  {
87  public:
89  std_msgs::Header header;
90  double value;
91  ValueStamped(const std_msgs::Header& aheader, double avalue):
92  header(aheader), value(avalue) {
93  }
94  ValueStamped() { }
95  };
96 
97  class Footcoords
98  {
99  public:
101  geometry_msgs::WrenchStamped,
102  geometry_msgs::WrenchStamped,
103  sensor_msgs::JointState,
104  geometry_msgs::PointStamped> SyncPolicy;
106  nav_msgs::Odometry,
107  sensor_msgs::Imu> OdomImuSyncPolicy;
108 
109  Footcoords();
110  virtual ~Footcoords();
111 
112  enum SupportLegStatus
113  {
115  };
116 
118  {
120  };
121 
122  protected:
123 
124  // methods
125 
126  /*
127  * virtual void filter(const geometry_msgs::WrenchStamped::ConstPtr& lfoot,
128  * const geometry_msgs::WrenchStamped::ConstPtr& rfoot);
129  */
130  virtual void filter(const jsk_footstep_controller::SynchronizedForces::ConstPtr& msg);
131  virtual bool computeMidCoords(const ros::Time& stamp);
132  virtual bool computeMidCoordsFromSingleLeg(const ros::Time& stamp,
133  bool use_left_leg);
134  virtual bool waitForEndEffectorTransformation(const ros::Time& stamp);
135  virtual bool waitForSensorFrameTransformation(const ros::Time& lstamp,
136  const ros::Time& rstamp,
137  const std::string& lsensor_frame,
138  const std::string& rsensor_frame);
139  virtual bool updateGroundTF();
140  virtual void publishTF(const ros::Time& stamp);
141  virtual void publishState(const std::string& state);
143  virtual void publishContactState(const ros::Time& stamp);
144  virtual double applyLowPassFilter(double current_val, double prev_val) const;
146  double threshold);
148  double threshold);
149  virtual bool resolveForceTf(const geometry_msgs::WrenchStamped& lfoot,
150  const geometry_msgs::WrenchStamped& rfoot,
151  tf::Vector3& lfoot_force, tf::Vector3& rfoot_force);
152  virtual void periodicTimerCallback(const ros::TimerEvent& event);
153  virtual void odomInitTriggerCallback(const std_msgs::Empty& trigger);
154  virtual void floorCoeffsCallback(const pcl_msgs::ModelCoefficients& coeffs);
155  virtual void odomImuCallback(const nav_msgs::Odometry::ConstPtr& odom_msg,
156  const sensor_msgs::Imu::ConstPtr& imu_msg);
157  // This callback is called when robot is put on the ground.
158  // virtual void odomInitCallback(const std_msgs::Empty& odom_init_msg);
159  virtual void synchronizeForces(const geometry_msgs::WrenchStamped::ConstPtr& lfoot,
160  const geometry_msgs::WrenchStamped::ConstPtr& rfoot,
161  const sensor_msgs::JointState::ConstPtr& joint_states,
162  const geometry_msgs::PointStamped::ConstPtr& zmp);
163  virtual void estimateOdometry();
164  virtual void estimateOdometryNaive();
165  virtual void estimateOdometryMainSupportLeg();
166  virtual void estimateOdometryZMPSupportLeg();
167  virtual void updateRobotModel(std::map<std::string, double>& joint_angles);
168  virtual void updateChain(std::map<std::string, double>& joint_angles,
169  KDL::Chain& chain,
170  tf::Pose& output_pose);
171  virtual void estimateVelocity(const ros::Time& stamp, std::map<std::string, double>& joint_angles);
172  virtual void computeVelicity(double dt,
173  std::map<std::string, double>& joint_angles,
174  KDL::Chain& chain,
175  geometry_msgs::Twist& output);
176  virtual float getYaw(const Eigen::Affine3d& pose);
177  virtual void getRollPitch(const Eigen::Affine3d& pose, float& roll, float& pitch);
178  // ros variables
179  boost::mutex mutex_;
180  Eigen::Affine3d odom_pose_;
181  Eigen::Affine3d odom_init_pose_;
184  //ros::Subscriber odom_sub_;
195  std::vector<float> floor_coeffs_;
196  KDL::Chain lfoot_chain_;
197  KDL::Chain rfoot_chain_;
215  // parameters
216  std::string zmp_frame_id_;
217  std::string output_frame_id_;
218  std::string parent_frame_id_;
219  std::string midcoords_frame_id_;
222  Eigen::Vector3f zmp_;
223  double force_thr_;
225  std::map<std::string, double> prev_joints_;
226  bool use_imu_;
229  std::string lfoot_frame_id_;
230  std::string rfoot_frame_id_;
231  std::string lfoot_sensor_frame_;
232  std::string rfoot_sensor_frame_;
233  std::string root_frame_id_;
234  std::string body_on_odom_frame_;
235  std::string odom_init_frame_id_;
242  double prev_lforce_;
243  double prev_rforce_;
244  double alpha_;
247  private:
248  };
249 }
250 #endif
jsk_footstep_controller::Footcoords::OdomStatus
OdomStatus
Definition: footcoords.h:149
jsk_footstep_controller::Footcoords::INITIALIZING
@ INITIALIZING
Definition: footcoords.h:151
jsk_footstep_controller::Footcoords::allValueSmallerThan
virtual bool allValueSmallerThan(TimeStampedVector< ValueStamped::Ptr > &values, double threshold)
Definition: footcoords.cpp:224
jsk_footstep_controller::Footcoords::support_status_
SupportLegStatus support_status_
Definition: footcoords.h:252
jsk_footstep_controller::Footcoords::pub_odom_init_pose_stamped_
ros::Publisher pub_odom_init_pose_stamped_
Definition: footcoords.h:244
jsk_footstep_controller::Footcoords::SupportLegStatus
SupportLegStatus
Definition: footcoords.h:144
jsk_footstep_controller::Footcoords::prev_lforce_
double prev_lforce_
Definition: footcoords.h:274
jsk_footstep_controller::Footcoords::sub_lfoot_force_
message_filters::Subscriber< geometry_msgs::WrenchStamped > sub_lfoot_force_
Definition: footcoords.h:221
jsk_footstep_controller::Footcoords::pub_low_level_
ros::Publisher pub_low_level_
Definition: footcoords.h:237
ros::Publisher
jsk_footstep_controller::Footcoords::locked_midcoords_to_odom_on_ground_
tf::Transform locked_midcoords_to_odom_on_ground_
Definition: footcoords.h:272
boost::shared_ptr
jsk_footstep_controller::Footcoords::RLEG_GROUND
@ RLEG_GROUND
Definition: footcoords.h:146
jsk_footstep_controller::Footcoords::rfoot_frame_id_
std::string rfoot_frame_id_
Definition: footcoords.h:262
jsk_footstep_controller::Footcoords::waitForEndEffectorTransformation
virtual bool waitForEndEffectorTransformation(const ros::Time &stamp)
Definition: footcoords.cpp:909
jsk_footstep_controller::Footcoords::rfoot_sensor_frame_
std::string rfoot_sensor_frame_
Definition: footcoords.h:264
jsk_footstep_controller::Footcoords::odom_init_frame_id_
std::string odom_init_frame_id_
Definition: footcoords.h:267
jsk_footstep_controller::Footcoords::output_frame_id_
std::string output_frame_id_
Definition: footcoords.h:249
jsk_footstep_controller::Footcoords::last_time_
ros::Time last_time_
Definition: footcoords.h:260
jsk_footstep_controller::Footcoords::RLEG_SUPPORT
@ RLEG_SUPPORT
Definition: footcoords.h:151
jsk_footstep_controller::Footcoords::rfoot_to_origin_pose_
tf::Pose rfoot_to_origin_pose_
Definition: footcoords.h:233
jsk_footstep_controller::Footcoords::odomInitTriggerCallback
virtual void odomInitTriggerCallback(const std_msgs::Empty &trigger)
Definition: footcoords.cpp:1053
jsk_footstep_controller::Footcoords::sub_zmp_
message_filters::Subscriber< geometry_msgs::PointStamped > sub_zmp_
Definition: footcoords.h:224
jsk_footstep_controller::Footcoords::computeMidCoords
virtual bool computeMidCoords(const ros::Time &stamp)
Definition: footcoords.cpp:838
jsk_footstep_controller::Footcoords::estimateVelocity
virtual void estimateVelocity(const ros::Time &stamp, std::map< std::string, double > &joint_angles)
Definition: footcoords.cpp:420
jsk_footstep_controller::Footcoords::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: footcoords.h:225
jsk_footstep_controller::Footcoords::body_on_odom_frame_
std::string body_on_odom_frame_
Definition: footcoords.h:266
jsk_footstep_controller::Footcoords::synchronizeForces
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)
Definition: footcoords.cpp:330
jsk_footstep_controller::Footcoords::floorCoeffsCallback
virtual void floorCoeffsCallback(const pcl_msgs::ModelCoefficients &coeffs)
Definition: footcoords.cpp:1083
jsk_footstep_controller::Footcoords::zmp_frame_id_
std::string zmp_frame_id_
Definition: footcoords.h:248
jsk_footstep_controller::Footcoords::zmp_
Eigen::Vector3f zmp_
Definition: footcoords.h:254
jsk_footstep_controller::Footcoords::publishState
virtual void publishState(const std::string &state)
Definition: footcoords.cpp:734
jsk_footstep_controller::Footcoords::pub_synchronized_forces_
ros::Publisher pub_synchronized_forces_
Definition: footcoords.h:238
jsk_footstep_controller::ValueStamped::ValueStamped
ValueStamped()
Definition: footcoords.h:126
jsk_footstep_controller::Footcoords::updateRobotModel
virtual void updateRobotModel(std::map< std::string, double > &joint_angles)
Definition: footcoords.cpp:383
jsk_footstep_controller::Footcoords::floor_coeffs_
std::vector< float > floor_coeffs_
Definition: footcoords.h:227
jsk_footstep_controller::Footcoords::lfoot_sensor_frame_
std::string lfoot_sensor_frame_
Definition: footcoords.h:263
jsk_footstep_controller::TimeStampedVector::removeBefore
void removeBefore(const ros::Time &stamp)
Definition: footcoords.h:132
time_synchronizer.h
jsk_footstep_controller::Footcoords::use_imu_yaw_
bool use_imu_yaw_
Definition: footcoords.h:259
jsk_footstep_controller::Footcoords::root_frame_id_
std::string root_frame_id_
Definition: footcoords.h:265
jsk_footstep_controller::Footcoords::LLEG_GROUND
@ LLEG_GROUND
Definition: footcoords.h:146
jsk_footstep_controller::TimeStampedVector::iterator
std::vector< T >::iterator iterator
Definition: footcoords.h:131
jsk_footstep_controller::Footcoords::estimateOdometryMainSupportLeg
virtual void estimateOdometryMainSupportLeg()
Definition: footcoords.cpp:574
jsk_footstep_controller::Footcoords::sampling_time_
double sampling_time_
Definition: footcoords.h:277
jsk_footstep_controller::Footcoords::invert_odom_init_
bool invert_odom_init_
Definition: footcoords.h:268
publisher.h
transform_broadcaster.h
jsk_footstep_controller::Footcoords::odom_status_
OdomStatus odom_status_
Definition: footcoords.h:253
diagnostic_updater.h
jsk_footstep_controller::Footcoords::estimateOdometryNaive
virtual void estimateOdometryNaive()
Definition: footcoords.cpp:512
jsk_footstep_controller::Footcoords::publish_odom_tf_
bool publish_odom_tf_
Definition: footcoords.h:278
jsk_footstep_controller::Footcoords::applyLowPassFilter
virtual double applyLowPassFilter(double current_val, double prev_val) const
Definition: footcoords.cpp:208
message_filters::Subscriber< nav_msgs::Odometry >
jsk_footstep_controller::Footcoords::midcoords_frame_id_
std::string midcoords_frame_id_
Definition: footcoords.h:251
jsk_footstep_controller::Footcoords::AIR
@ AIR
Definition: footcoords.h:146
jsk_footstep_controller::Footcoords::BOTH_GROUND
@ BOTH_GROUND
Definition: footcoords.h:146
jsk_footstep_controller::Footcoords::waitForSensorFrameTransformation
virtual bool waitForSensorFrameTransformation(const ros::Time &lstamp, const ros::Time &rstamp, const std::string &lsensor_frame, const std::string &rsensor_frame)
Definition: footcoords.cpp:886
jsk_footstep_controller::Footcoords::pub_contact_state_
ros::Publisher pub_contact_state_
Definition: footcoords.h:236
jsk_footstep_controller::Footcoords::updateChain
virtual void updateChain(std::map< std::string, double > &joint_angles, KDL::Chain &chain, tf::Pose &output_pose)
Definition: footcoords.cpp:360
jsk_footstep_controller::Footcoords::pub_leg_odometory_
ros::Publisher pub_leg_odometory_
Definition: footcoords.h:241
jsk_footstep_controller::Footcoords::parent_frame_id_
std::string parent_frame_id_
Definition: footcoords.h:250
jsk_footstep_controller::Footcoords::computeVelicity
virtual void computeVelicity(double dt, std::map< std::string, double > &joint_angles, KDL::Chain &chain, geometry_msgs::Twist &output)
Definition: footcoords.cpp:395
jsk_footstep_controller::Footcoords::lfoot_chain_
KDL::Chain lfoot_chain_
Definition: footcoords.h:228
jsk_footstep_controller::Footcoords::prev_joints_
std::map< std::string, double > prev_joints_
Definition: footcoords.h:257
plane.h
jsk_footstep_controller::Footcoords::publishTF
virtual void publishTF(const ros::Time &stamp)
Definition: footcoords.cpp:986
jsk_footstep_controller::Footcoords::filter
virtual void filter(const jsk_footstep_controller::SynchronizedForces::ConstPtr &msg)
Definition: footcoords.cpp:437
jsk_footstep_controller::Footcoords::mutex_
boost::mutex mutex_
Definition: footcoords.h:211
jsk_footstep_controller::ValueStamped::header
std_msgs::Header header
Definition: footcoords.h:121
tf::TransformBroadcaster
jsk_footstep_controller::Footcoords::pub_debug_lfoot_pos_
ros::Publisher pub_debug_lfoot_pos_
Definition: footcoords.h:239
jsk_footstep_controller::Footcoords::odomImuCallback
virtual void odomImuCallback(const nav_msgs::Odometry::ConstPtr &odom_msg, const sensor_msgs::Imu::ConstPtr &imu_msg)
Definition: footcoords.cpp:1115
subscriber.h
jsk_footstep_controller::Footcoords::sub_joint_states_
message_filters::Subscriber< sensor_msgs::JointState > sub_joint_states_
Definition: footcoords.h:223
model.h
jsk_footstep_controller::Footcoords::updateGroundTF
virtual bool updateGroundTF()
Definition: footcoords.cpp:938
jsk_footstep_controller
Definition: footcoords.h:61
jsk_footstep_controller::Footcoords::getRollPitch
virtual void getRollPitch(const Eigen::Affine3d &pose, float &roll, float &pitch)
Definition: footcoords.cpp:969
jsk_footstep_controller::Footcoords::root_link_pose_
tf::Transform root_link_pose_
Definition: footcoords.h:271
jsk_footstep_controller::Footcoords::odom_pose_
Eigen::Affine3d odom_pose_
Definition: footcoords.h:212
jsk_footstep_controller::Footcoords::resolveForceTf
virtual bool resolveForceTf(const geometry_msgs::WrenchStamped &lfoot, const geometry_msgs::WrenchStamped &rfoot, tf::Vector3 &lfoot_force, tf::Vector3 &rfoot_force)
Definition: footcoords.cpp:235
jsk_footstep_controller::Footcoords::odom_init_pose_
Eigen::Affine3d odom_init_pose_
Definition: footcoords.h:213
jsk_footstep_controller::Footcoords::periodic_update_timer_
ros::Timer periodic_update_timer_
Definition: footcoords.h:214
jsk_footstep_controller::ValueStamped::Ptr
boost::shared_ptr< ValueStamped > Ptr
Definition: footcoords.h:120
stamp
stamp
ros::TimerEvent
tf::Transform
jsk_footstep_controller::Footcoords::estimated_odom_pose_
tf::Pose estimated_odom_pose_
Definition: footcoords.h:234
jsk_footstep_controller::Footcoords::estimateOdometry
virtual void estimateOdometry()
Definition: footcoords.cpp:506
jsk_footstep_controller::Footcoords::force_thr_
double force_thr_
Definition: footcoords.h:255
jsk_footstep_controller::Footcoords::alpha_
double alpha_
Definition: footcoords.h:276
jsk_footstep_controller::Footcoords::before_on_the_air_
bool before_on_the_air_
Definition: footcoords.h:256
kdl_parser.hpp
jsk_footstep_controller::Footcoords::tf_listener_
boost::shared_ptr< tf::TransformListener > tf_listener_
Definition: footcoords.h:245
jsk_footstep_controller::Footcoords::prev_rforce_
double prev_rforce_
Definition: footcoords.h:275
jsk_footstep_controller::TimeStampedVector
Definition: footcoords.h:96
jsk_footstep_controller::Footcoords::sub_rfoot_force_
message_filters::Subscriber< geometry_msgs::WrenchStamped > sub_rfoot_force_
Definition: footcoords.h:222
jsk_footstep_controller::Footcoords::publishContactState
virtual void publishContactState(const ros::Time &stamp)
Definition: footcoords.cpp:741
jsk_footstep_controller::Footcoords
Definition: footcoords.h:129
jsk_footstep_controller::Footcoords::LLEG_SUPPORT
@ LLEG_SUPPORT
Definition: footcoords.h:151
transform_listener.h
jsk_footstep_controller::ValueStamped
Definition: footcoords.h:117
jsk_footstep_controller::Footcoords::pub_state_
ros::Publisher pub_state_
Definition: footcoords.h:235
jsk_footstep_controller::Footcoords::~Footcoords
virtual ~Footcoords()
Definition: footcoords.cpp:183
jsk_footstep_controller::Footcoords::lfoot_pose_
tf::Pose lfoot_pose_
Definition: footcoords.h:230
jsk_footstep_controller::Footcoords::getYaw
virtual float getYaw(const Eigen::Affine3d &pose)
Definition: footcoords.cpp:977
jsk_footstep_controller::Footcoords::SyncPolicy
message_filters::sync_policies::ExactTime< geometry_msgs::WrenchStamped, geometry_msgs::WrenchStamped, sensor_msgs::JointState, geometry_msgs::PointStamped > SyncPolicy
Definition: footcoords.h:136
jsk_footstep_controller::Footcoords::odom_imu_sync_
boost::shared_ptr< message_filters::Synchronizer< OdomImuSyncPolicy > > odom_imu_sync_
Definition: footcoords.h:219
jsk_footstep_controller::Footcoords::floor_coeffs_sub_
ros::Subscriber floor_coeffs_sub_
Definition: footcoords.h:226
jsk_footstep_controller::Footcoords::rfoot_chain_
KDL::Chain rfoot_chain_
Definition: footcoords.h:229
jsk_footstep_controller::Footcoords::synchronized_forces_sub_
ros::Subscriber synchronized_forces_sub_
Definition: footcoords.h:220
jsk_footstep_controller::Footcoords::diagnostic_updater_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
Definition: footcoords.h:273
ros::Time
jsk_footstep_controller::Footcoords::use_imu_
bool use_imu_
Definition: footcoords.h:258
jsk_footstep_controller::Footcoords::lfoot_frame_id_
std::string lfoot_frame_id_
Definition: footcoords.h:261
jsk_footstep_controller::Footcoords::allValueLargerThan
virtual bool allValueLargerThan(TimeStampedVector< ValueStamped::Ptr > &values, double threshold)
Definition: footcoords.cpp:213
jsk_footstep_controller::Footcoords::OdomImuSyncPolicy
message_filters::sync_policies::ExactTime< nav_msgs::Odometry, sensor_msgs::Imu > OdomImuSyncPolicy
Definition: footcoords.h:139
jsk_footstep_controller::Footcoords::UNINITIALIZED
@ UNINITIALIZED
Definition: footcoords.h:151
jsk_footstep_controller::Footcoords::imu_sub_
message_filters::Subscriber< sensor_msgs::Imu > imu_sub_
Definition: footcoords.h:218
jsk_footstep_controller::Footcoords::odom_sub_
message_filters::Subscriber< nav_msgs::Odometry > odom_sub_
Definition: footcoords.h:217
jsk_footstep_controller::ValueStamped::value
double value
Definition: footcoords.h:122
synchronizer.h
jsk_footstep_controller::Footcoords::lfoot_to_origin_pose_
tf::Pose lfoot_to_origin_pose_
Definition: footcoords.h:232
diagnostic_updater::DiagnosticStatusWrapper
jsk_footstep_controller::Footcoords::computeMidCoordsFromSingleLeg
virtual bool computeMidCoordsFromSingleLeg(const ros::Time &stamp, bool use_left_leg)
Definition: footcoords.cpp:793
jsk_footstep_controller::Footcoords::ground_transform_
tf::Transform ground_transform_
Definition: footcoords.h:269
jsk_footstep_controller::Footcoords::tf_broadcaster_
tf::TransformBroadcaster tf_broadcaster_
Definition: footcoords.h:246
jsk_footstep_controller::Footcoords::Footcoords
Footcoords()
Definition: footcoords.cpp:83
jsk_footstep_controller::Footcoords::rfoot_pose_
tf::Pose rfoot_pose_
Definition: footcoords.h:231
jsk_footstep_controller::Footcoords::pub_odom_init_transform_
ros::Publisher pub_odom_init_transform_
Definition: footcoords.h:243
jsk_footstep_controller::Footcoords::midcoords_
tf::Transform midcoords_
Definition: footcoords.h:270
message_filters::sync_policies::ExactTime
jsk_footstep_controller::Footcoords::pub_twist_
ros::Publisher pub_twist_
Definition: footcoords.h:242
ros::Duration
ros::Timer
jsk_footstep_controller::Footcoords::updateLegDiagnostics
virtual void updateLegDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: footcoords.cpp:188
jsk_footstep_controller::Footcoords::pub_debug_rfoot_pos_
ros::Publisher pub_debug_rfoot_pos_
Definition: footcoords.h:240
jsk_footstep_controller::Footcoords::odom_init_trigger_sub_
ros::Subscriber odom_init_trigger_sub_
Definition: footcoords.h:215
jsk_footstep_controller::Footcoords::estimateOdometryZMPSupportLeg
virtual void estimateOdometryZMPSupportLeg()
Definition: footcoords.cpp:653
jsk_footstep_controller::Footcoords::periodicTimerCallback
virtual void periodicTimerCallback(const ros::TimerEvent &event)
Definition: footcoords.cpp:281
ros::Subscriber


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