Controller.h File Reference
#include <mc_control/api.h>
#include <mc_control/fsm/Controller.h>
#include <mc_control/mc_controller.h>
#include <mc_rtc/logging.h>
#include <mc_rtc/ros.h>
#include <ros/ros.h>
#include <tf2_ros/transform_broadcaster.h>
#include <visualization_msgs/MarkerArray.h>
#include <lipm_walking/Contact.h>
#include <lipm_walking/FloatingBaseObserver.h>
#include <lipm_walking/FootstepPlan.h>
#include <lipm_walking/ModelPredictiveControl.h>
#include <lipm_walking/NetWrenchObserver.h>
#include <lipm_walking/Pendulum.h>
#include <lipm_walking/PlanInterpolator.h>
#include <lipm_walking/Sole.h>
#include <lipm_walking/Stabilizer.h>
#include <lipm_walking/utils/LowPassVelocityFilter.h>
#include <mutex>
#include <thread>

Go to the source code of this file.

Classes

struct  lipm_walking::Controller
 Main controller class. More...
 

Namespaces

 lipm_walking
 Main controller namespace.
 

Variables

constexpr double lipm_walking::PREVIEW_UPDATE_PERIOD = ModelPredictiveControl::SAMPLING_PERIOD
 Preview update period, same as MPC sampling period. More...