|
| bool | configure (ros::NodeHandle &nh, const teb_local_planner::ObstContainer &obstacles, teb_local_planner::RobotFootprintModelPtr robot_model, const std::vector< teb_local_planner::PoseSE2 > &via_points) |
| |
| | Controller ()=default |
| |
| StageInequalitySE2::Ptr | getInequalityConstraint () |
| |
| corbo::ControllerInterface::Ptr | getInstance () const override |
| |
| RobotDynamicsInterface::Ptr | getRobotDynamics () |
| |
| virtual bool | isPoseTrajectoryFeasible (base_local_planner::CostmapModel *costmap_model, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0, double min_resolution_collision_check_angular=M_PI, int look_ahead_idx=-1) |
| | Check whether the planned trajectory is feasible or not. More...
|
| |
| void | publishOptimalControlResult () |
| |
| void | reset () override |
| |
| void | setInitialPlanEstimateOrientation (bool estimate) |
| |
| void | setOptimalControlProblem (corbo::OptimalControlProblemInterface::Ptr ocp)=delete |
| |
| void | stateFeedbackCallback (const mpc_local_planner_msgs::StateFeedback::ConstPtr &msg) |
| |
| bool | step (const PoseSE2 &start, const PoseSE2 &goal, const geometry_msgs::Twist &vel, double dt, ros::Time t, corbo::TimeSeries::Ptr u_seq, corbo::TimeSeries::Ptr x_seq) |
| |
| bool | step (const std::vector< geometry_msgs::PoseStamped > &initial_plan, const geometry_msgs::Twist &vel, double dt, ros::Time t, corbo::TimeSeries::Ptr u_seq, corbo::TimeSeries::Ptr x_seq) |
| |
| bool | getAutoUpdatePreviousControl () const |
| |
| void | getAvailableSignals (SignalTargetInterface &signal_target, const std::string &ns="") const override |
| |
| double | getControlDuration () const override |
| |
| int | getControlInputDimension () const override |
| |
| const int & | getNumOcpIterations () const |
| |
| OptimalControlProblemInterface::Ptr | getOptimalControlProblem () |
| |
| int | getStateDimension () const override |
| |
| ControllerStatistics::Ptr | getStatistics () const override |
| |
| bool | hasPiecewiseConstantControls () const override |
| |
| bool | initialize (const StateVector &x, ReferenceTrajectoryInterface &expected_xref, ReferenceTrajectoryInterface &expected_uref, const Duration &expected_dt, const Time &t, ReferenceTrajectoryInterface *sref=nullptr) override |
| |
| const bool & | isPublishPrediction () const |
| |
| | PredictiveController () |
| |
| bool | providesFutureControls () const override |
| |
| bool | providesFutureStates () const override |
| |
| void | sendSignals (double t, SignalTargetInterface &signal_target, const std::string &ns="") const override |
| |
| void | setAutoUpdatePreviousControl (bool enable) |
| |
| void | setNumOcpIterations (int ocp_iter) |
| |
| void | setOptimalControlProblem (OptimalControlProblemInterface::Ptr ocp) |
| |
| void | setOutputControlSequenceLenght (bool activate) |
| |
| void | setOutputStateSequenceLenght (bool activate) |
| |
| void | setPublishPrediction (bool publish) |
| |
| bool | step (const StateVector &x, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, const Duration &dt, const Time &t, TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface *signal_target=nullptr, ReferenceTrajectoryInterface *sref=nullptr, ReferenceTrajectoryInterface *xinit=nullptr, ReferenceTrajectoryInterface *uinit=nullptr, const std::string &ns="") override |
| |
| bool | supportsAsynchronousControl () const override |
| |
| virtual bool | step (const StateVector &x, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, const Duration &dt, const Time &t, ControlVector &u, SignalTargetInterface *signal_target=nullptr, const std::string &ns="") |
| |
| virtual | ~ControllerInterface () |
| |