#include <footcoords.h>
Definition at line 97 of file footcoords.h.
typedef message_filters::sync_policies::ExactTime< nav_msgs::Odometry, sensor_msgs::Imu> jsk_footstep_controller::Footcoords::OdomImuSyncPolicy |
Definition at line 107 of file footcoords.h.
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 104 of file footcoords.h.
Definition at line 117 of file footcoords.h.
Definition at line 112 of file footcoords.h.
Definition at line 51 of file footcoords.cpp.
jsk_footstep_controller::Footcoords::~Footcoords | ( | ) | [virtual] |
Definition at line 148 of file footcoords.cpp.
bool jsk_footstep_controller::Footcoords::allValueLargerThan | ( | TimeStampedVector< ValueStamped::Ptr > & | values, |
double | threshold | ||
) | [protected, virtual] |
Definition at line 178 of file footcoords.cpp.
bool jsk_footstep_controller::Footcoords::allValueSmallerThan | ( | TimeStampedVector< ValueStamped::Ptr > & | values, |
double | threshold | ||
) | [protected, virtual] |
Definition at line 189 of file footcoords.cpp.
double jsk_footstep_controller::Footcoords::applyLowPassFilter | ( | double | current_val, |
double | prev_val | ||
) | const [protected, virtual] |
Definition at line 173 of file footcoords.cpp.
bool jsk_footstep_controller::Footcoords::computeMidCoords | ( | const ros::Time & | stamp | ) | [protected, virtual] |
Definition at line 803 of file footcoords.cpp.
bool jsk_footstep_controller::Footcoords::computeMidCoordsFromSingleLeg | ( | const ros::Time & | stamp, |
bool | use_left_leg | ||
) | [protected, virtual] |
Definition at line 758 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::computeVelicity | ( | double | dt, |
std::map< std::string, double > & | joint_angles, | ||
KDL::Chain & | chain, | ||
geometry_msgs::Twist & | output | ||
) | [protected, virtual] |
Definition at line 360 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::estimateOdometry | ( | ) | [protected, virtual] |
Definition at line 471 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::estimateOdometryMainSupportLeg | ( | ) | [protected, virtual] |
Definition at line 539 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::estimateOdometryNaive | ( | ) | [protected, virtual] |
Definition at line 477 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::estimateOdometryZMPSupportLeg | ( | ) | [protected, virtual] |
Definition at line 618 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::estimateVelocity | ( | const ros::Time & | stamp, |
std::map< std::string, double > & | joint_angles | ||
) | [protected, virtual] |
Definition at line 385 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::filter | ( | const jsk_footstep_controller::SynchronizedForces::ConstPtr & | msg | ) | [protected, virtual] |
Definition at line 402 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::floorCoeffsCallback | ( | const pcl_msgs::ModelCoefficients & | coeffs | ) | [protected, virtual] |
Definition at line 1048 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::getRollPitch | ( | const Eigen::Affine3d & | pose, |
float & | roll, | ||
float & | pitch | ||
) | [protected, virtual] |
Definition at line 934 of file footcoords.cpp.
float jsk_footstep_controller::Footcoords::getYaw | ( | const Eigen::Affine3d & | pose | ) | [protected, virtual] |
Definition at line 942 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::odomImuCallback | ( | const nav_msgs::Odometry::ConstPtr & | odom_msg, |
const sensor_msgs::Imu::ConstPtr & | imu_msg | ||
) | [protected, virtual] |
Definition at line 1080 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::odomInitTriggerCallback | ( | const std_msgs::Empty & | trigger | ) | [protected, virtual] |
Definition at line 1018 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::periodicTimerCallback | ( | const ros::TimerEvent & | event | ) | [protected, virtual] |
Definition at line 246 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::publishContactState | ( | const ros::Time & | stamp | ) | [protected, virtual] |
Definition at line 706 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::publishState | ( | const std::string & | state | ) | [protected, virtual] |
Definition at line 699 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::publishTF | ( | const ros::Time & | stamp | ) | [protected, virtual] |
Definition at line 951 of file footcoords.cpp.
bool jsk_footstep_controller::Footcoords::resolveForceTf | ( | const geometry_msgs::WrenchStamped & | lfoot, |
const geometry_msgs::WrenchStamped & | rfoot, | ||
tf::Vector3 & | lfoot_force, | ||
tf::Vector3 & | rfoot_force | ||
) | [protected, virtual] |
Definition at line 200 of file footcoords.cpp.
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 | ||
) | [protected, virtual] |
Definition at line 295 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::updateChain | ( | std::map< std::string, double > & | joint_angles, |
KDL::Chain & | chain, | ||
tf::Pose & | output_pose | ||
) | [protected, virtual] |
Definition at line 325 of file footcoords.cpp.
bool jsk_footstep_controller::Footcoords::updateGroundTF | ( | ) | [protected, virtual] |
Definition at line 903 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::updateLegDiagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [protected, virtual] |
Definition at line 153 of file footcoords.cpp.
void jsk_footstep_controller::Footcoords::updateRobotModel | ( | std::map< std::string, double > & | joint_angles | ) | [protected, virtual] |
Definition at line 348 of file footcoords.cpp.
bool jsk_footstep_controller::Footcoords::waitForEndEffectorTransformation | ( | const ros::Time & | stamp | ) | [protected, virtual] |
Definition at line 874 of file footcoords.cpp.
bool jsk_footstep_controller::Footcoords::waitForSensorFrameTransformation | ( | const ros::Time & | lstamp, |
const ros::Time & | rstamp, | ||
const std::string & | lsensor_frame, | ||
const std::string & | rsensor_frame | ||
) | [protected, virtual] |
Definition at line 851 of file footcoords.cpp.
double jsk_footstep_controller::Footcoords::alpha_ [protected] |
Definition at line 244 of file footcoords.h.
bool jsk_footstep_controller::Footcoords::before_on_the_air_ [protected] |
Definition at line 224 of file footcoords.h.
Definition at line 234 of file footcoords.h.
boost::shared_ptr<diagnostic_updater::Updater> jsk_footstep_controller::Footcoords::diagnostic_updater_ [protected] |
Definition at line 241 of file footcoords.h.
Definition at line 202 of file footcoords.h.
std::vector<float> jsk_footstep_controller::Footcoords::floor_coeffs_ [protected] |
Definition at line 195 of file footcoords.h.
Definition at line 194 of file footcoords.h.
double jsk_footstep_controller::Footcoords::force_thr_ [protected] |
Definition at line 223 of file footcoords.h.
Definition at line 237 of file footcoords.h.
message_filters::Subscriber<sensor_msgs::Imu> jsk_footstep_controller::Footcoords::imu_sub_ [protected] |
Definition at line 186 of file footcoords.h.
bool jsk_footstep_controller::Footcoords::invert_odom_init_ [protected] |
Definition at line 236 of file footcoords.h.
Definition at line 228 of file footcoords.h.
Definition at line 196 of file footcoords.h.
Definition at line 229 of file footcoords.h.
Definition at line 198 of file footcoords.h.
Definition at line 231 of file footcoords.h.
Definition at line 200 of file footcoords.h.
Definition at line 240 of file footcoords.h.
Definition at line 238 of file footcoords.h.
Definition at line 219 of file footcoords.h.
Definition at line 179 of file footcoords.h.
boost::shared_ptr<message_filters::Synchronizer<OdomImuSyncPolicy> > jsk_footstep_controller::Footcoords::odom_imu_sync_ [protected] |
Definition at line 187 of file footcoords.h.
Definition at line 235 of file footcoords.h.
Eigen::Affine3d jsk_footstep_controller::Footcoords::odom_init_pose_ [protected] |
Definition at line 181 of file footcoords.h.
Definition at line 183 of file footcoords.h.
Eigen::Affine3d jsk_footstep_controller::Footcoords::odom_pose_ [protected] |
Definition at line 180 of file footcoords.h.
Definition at line 221 of file footcoords.h.
message_filters::Subscriber<nav_msgs::Odometry> jsk_footstep_controller::Footcoords::odom_sub_ [protected] |
Definition at line 185 of file footcoords.h.
Definition at line 217 of file footcoords.h.
Definition at line 218 of file footcoords.h.
Definition at line 182 of file footcoords.h.
std::map<std::string, double> jsk_footstep_controller::Footcoords::prev_joints_ [protected] |
Definition at line 225 of file footcoords.h.
double jsk_footstep_controller::Footcoords::prev_lforce_ [protected] |
Definition at line 242 of file footcoords.h.
double jsk_footstep_controller::Footcoords::prev_rforce_ [protected] |
Definition at line 243 of file footcoords.h.
Definition at line 204 of file footcoords.h.
Definition at line 207 of file footcoords.h.
Definition at line 208 of file footcoords.h.
Definition at line 209 of file footcoords.h.
Definition at line 205 of file footcoords.h.
Definition at line 212 of file footcoords.h.
Definition at line 211 of file footcoords.h.
Definition at line 203 of file footcoords.h.
Definition at line 206 of file footcoords.h.
Definition at line 210 of file footcoords.h.
bool jsk_footstep_controller::Footcoords::publish_odom_tf_ [protected] |
Definition at line 246 of file footcoords.h.
Definition at line 197 of file footcoords.h.
Definition at line 230 of file footcoords.h.
Definition at line 199 of file footcoords.h.
Definition at line 232 of file footcoords.h.
Definition at line 201 of file footcoords.h.
Definition at line 233 of file footcoords.h.
Definition at line 239 of file footcoords.h.
double jsk_footstep_controller::Footcoords::sampling_time_ [protected] |
Definition at line 245 of file footcoords.h.
message_filters::Subscriber<sensor_msgs::JointState> jsk_footstep_controller::Footcoords::sub_joint_states_ [protected] |
Definition at line 191 of file footcoords.h.
message_filters::Subscriber<geometry_msgs::WrenchStamped> jsk_footstep_controller::Footcoords::sub_lfoot_force_ [protected] |
Definition at line 189 of file footcoords.h.
message_filters::Subscriber<geometry_msgs::WrenchStamped> jsk_footstep_controller::Footcoords::sub_rfoot_force_ [protected] |
Definition at line 190 of file footcoords.h.
message_filters::Subscriber<geometry_msgs::PointStamped> jsk_footstep_controller::Footcoords::sub_zmp_ [protected] |
Definition at line 192 of file footcoords.h.
Definition at line 220 of file footcoords.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_footstep_controller::Footcoords::sync_ [protected] |
Definition at line 193 of file footcoords.h.
Definition at line 188 of file footcoords.h.
Definition at line 214 of file footcoords.h.
boost::shared_ptr<tf::TransformListener> jsk_footstep_controller::Footcoords::tf_listener_ [protected] |
Definition at line 213 of file footcoords.h.
bool jsk_footstep_controller::Footcoords::use_imu_ [protected] |
Definition at line 226 of file footcoords.h.
bool jsk_footstep_controller::Footcoords::use_imu_yaw_ [protected] |
Definition at line 227 of file footcoords.h.
Eigen::Vector3f jsk_footstep_controller::Footcoords::zmp_ [protected] |
Definition at line 222 of file footcoords.h.
Definition at line 216 of file footcoords.h.