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>
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>
57 #include <kdl/tree.hpp>
58 #include <kdl/chainjnttojacsolver.hpp>
67 typedef typename std::vector<T>::iterator
iterator;
70 for (
iterator it = std::vector<T>::begin();
71 it != std::vector<T>::end();) {
91 ValueStamped(
const std_msgs::Header& aheader,
double avalue):
101 geometry_msgs::WrenchStamped,
102 geometry_msgs::WrenchStamped,
103 sensor_msgs::JointState,
130 virtual void filter(
const jsk_footstep_controller::SynchronizedForces::ConstPtr& msg);
137 const std::string& lsensor_frame,
138 const std::string& rsensor_frame);
150 const geometry_msgs::WrenchStamped& rfoot,
151 tf::Vector3& lfoot_force, tf::Vector3& rfoot_force);
155 virtual void odomImuCallback(
const nav_msgs::Odometry::ConstPtr& odom_msg,
156 const sensor_msgs::Imu::ConstPtr& imu_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);
168 virtual void updateChain(std::map<std::string, double>& joint_angles,
173 std::map<std::string, double>& joint_angles,
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);