controller.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020, Christoph Rösmann, All rights reserved.
6  *
7  * This program is free software: you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation, either version 3 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <https://www.gnu.org/licenses/>.
19  *
20  * Authors: Christoph Rösmann
21  *********************************************************************/
22 
23 #ifndef CONTROLLER_H_
24 #define CONTROLLER_H_
25 
27 
33 
34 #include <mpc_local_planner_msgs/StateFeedback.h>
35 
37 
38 #include <ros/subscriber.h>
39 #include <ros/time.h>
40 
41 #include <memory>
42 #include <mutex>
43 
44 namespace mpc_local_planner {
45 
54 {
55  public:
56  using Ptr = std::shared_ptr<Controller>;
58 
59  Controller() = default;
60 
62  const std::vector<teb_local_planner::PoseSE2>& via_points);
63  bool step(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist& vel, double dt, ros::Time t, corbo::TimeSeries::Ptr u_seq,
65 
66  bool step(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist& vel, double dt, ros::Time t,
68 
69  // implements interface method
70  corbo::ControllerInterface::Ptr getInstance() const override { return std::make_shared<Controller>(); }
71  static corbo::ControllerInterface::Ptr getInstanceStatic() { return std::make_shared<Controller>(); }
72 
74 
77 
78  void stateFeedbackCallback(const mpc_local_planner_msgs::StateFeedback::ConstPtr& msg);
79 
81 
83 
99  virtual bool isPoseTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
100  double inscribed_radius = 0.0, double circumscribed_radius = 0.0,
101  double min_resolution_collision_check_angular = M_PI, int look_ahead_idx = -1);
102 
103  // implements interface method
104  void reset() override;
105 
106  protected:
112  const std::vector<teb_local_planner::PoseSE2>& via_points);
113 
114  bool generateInitialStateTrajectory(const Eigen::VectorXd& x0, const Eigen::VectorXd& xf,
115  const std::vector<geometry_msgs::PoseStamped>& initial_plan, bool backward);
116 
117  std::string _robot_type;
123 
125  bool _ocp_successful = false;
126  std::size_t _ocp_seq = 0;
127  bool _publish_ocp_results = false;
128  bool _print_cpu_time = false;
129 
130  bool _prefer_x_feedback = false; // prefer state feedback over odometry feedback
132  std::mutex _x_feedback_mutex;
134  Eigen::VectorXd _recent_x_feedback;
135 
137  double _force_reinit_new_goal_dist = 1.0;
138  double _force_reinit_new_goal_angular = 0.5 * M_PI;
141  bool _guess_backwards_motion = true;
142  int _force_reinit_num_steps = 0;
143 };
144 
145 } // namespace mpc_local_planner
146 
147 #endif // CONTROLLER_H_
mpc_local_planner::Controller::_x_feedback_sub
ros::Subscriber _x_feedback_sub
Definition: controller.h:171
predictive_controller.h
structured_optimal_control_problem.h
mpc_local_planner::Controller::isPoseTrajectoryFeasible
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.
Definition: controller.cpp:879
ros::Publisher
boost::shared_ptr< BaseRobotFootprintModel >
via_points
ViaPointContainer via_points
mpc_local_planner::Controller::_solver
corbo::NlpSolverInterface::Ptr _solver
Definition: controller.h:160
time.h
mpc_local_planner::Controller::_force_reinit_num_steps
int _force_reinit_num_steps
Definition: controller.h:182
stage_inequality_se2.h
mpc_local_planner::Controller::getInstanceStatic
static corbo::ControllerInterface::Ptr getInstanceStatic()
Definition: controller.h:111
mpc_local_planner::Controller::configureSolver
corbo::NlpSolverInterface::Ptr configureSolver(const ros::NodeHandle &nh)
Definition: controller.cpp:400
mpc_local_planner::Controller::configureGrid
corbo::DiscretizationGridInterface::Ptr configureGrid(const ros::NodeHandle &nh)
Definition: controller.cpp:245
mpc_local_planner::Controller::_force_reinit_new_goal_dist
double _force_reinit_new_goal_dist
Definition: controller.h:177
robot_dynamics_interface.h
mpc_local_planner::Controller::getInequalityConstraint
StageInequalitySE2::Ptr getInequalityConstraint()
Definition: controller.h:116
mpc_local_planner::Controller::getRobotDynamics
RobotDynamicsInterface::Ptr getRobotDynamics()
Definition: controller.h:115
mpc_local_planner::Controller::_initial_plan_estimate_orientation
bool _initial_plan_estimate_orientation
Definition: controller.h:180
mpc_local_planner::Controller::configure
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)
Definition: controller.cpp:78
corbo::NlpSolverInterface::Ptr
std::shared_ptr< NlpSolverInterface > Ptr
mpc_local_planner::Controller::setOptimalControlProblem
void setOptimalControlProblem(corbo::OptimalControlProblemInterface::Ptr ocp)=delete
mpc_local_planner::Controller::reset
void reset() override
Definition: controller.cpp:243
mpc_local_planner
Definition: controller.h:44
mpc_local_planner::Controller::_force_reinit_new_goal_angular
double _force_reinit_new_goal_angular
Definition: controller.h:178
mpc_local_planner::Controller::_publish_ocp_results
bool _publish_ocp_results
Definition: controller.h:167
corbo::OptimalControlProblemInterface::Ptr
std::shared_ptr< OptimalControlProblemInterface > Ptr
corbo::DiscretizationGridInterface::Ptr
std::shared_ptr< DiscretizationGridInterface > Ptr
mpc_local_planner::Controller::_robot_type
std::string _robot_type
Definition: controller.h:157
base_local_planner::CostmapModel
mpc_local_planner::Controller::_x_seq_init
corbo::DiscreteTimeReferenceTrajectory _x_seq_init
Definition: controller.h:179
mpc_local_planner::Controller::_inequality_constraint
StageInequalitySE2::Ptr _inequality_constraint
Definition: controller.h:161
corbo::DiscreteTimeReferenceTrajectory
subscriber.h
mpc_local_planner::Controller::setInitialPlanEstimateOrientation
void setInitialPlanEstimateOrientation(bool estimate)
Definition: controller.h:122
costmap_model.h
teb_local_planner::ObstContainer
std::vector< ObstaclePtr > ObstContainer
mpc_local_planner::Controller::publishOptimalControlResult
void publishOptimalControlResult()
Definition: controller.cpp:217
mpc_local_planner::Controller::_dynamics
RobotDynamicsInterface::Ptr _dynamics
Definition: controller.h:159
mpc_local_planner::Controller::_structured_ocp
corbo::StructuredOptimalControlProblem::Ptr _structured_ocp
Definition: controller.h:162
mpc_local_planner::Controller::Controller
Controller()=default
pose_se2.h
corbo::ControllerInterface::Ptr
std::shared_ptr< ControllerInterface > Ptr
mpc_local_planner::Controller::_recent_x_time
ros::Time _recent_x_time
Definition: controller.h:173
mpc_local_planner::Controller::PoseSE2
teb_local_planner::PoseSE2 PoseSE2
Definition: controller.h:97
mpc_local_planner::Controller::_ocp_result_pub
ros::Publisher _ocp_result_pub
Definition: controller.h:164
mpc_local_planner::Controller::stateFeedbackCallback
void stateFeedbackCallback(const mpc_local_planner_msgs::StateFeedback::ConstPtr &msg)
Definition: controller.cpp:201
mpc_local_planner::Controller::step
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)
Definition: controller.cpp:122
mpc_local_planner::Controller::_grid
corbo::DiscretizationGridInterface::Ptr _grid
Definition: controller.h:158
start
ROSCPP_DECL void start()
teb_local_planner::PoseSE2
mpc_local_planner::Controller::_guess_backwards_motion
bool _guess_backwards_motion
Definition: controller.h:181
ros::Time
mpc_local_planner::Controller::_recent_x_feedback
Eigen::VectorXd _recent_x_feedback
Definition: controller.h:174
mpc_local_planner::StageInequalitySE2::Ptr
std::shared_ptr< StageInequalitySE2 > Ptr
Definition: stage_inequality_se2.h:92
mpc_local_planner::Controller::_ocp_seq
std::size_t _ocp_seq
Definition: controller.h:166
mpc_local_planner::Controller::Ptr
std::shared_ptr< Controller > Ptr
Definition: controller.h:96
mpc_local_planner::Controller::_print_cpu_time
bool _print_cpu_time
Definition: controller.h:168
mpc_local_planner::Controller::configureOcp
corbo::StructuredOptimalControlProblem::Ptr configureOcp(const ros::NodeHandle &nh, const teb_local_planner::ObstContainer &obstacles, teb_local_planner::RobotFootprintModelPtr robot_model, const std::vector< teb_local_planner::PoseSE2 > &via_points)
Definition: controller.cpp:503
mpc_local_planner::Controller::generateInitialStateTrajectory
bool generateInitialStateTrajectory(const Eigen::VectorXd &x0, const Eigen::VectorXd &xf, const std::vector< geometry_msgs::PoseStamped > &initial_plan, bool backward)
Definition: controller.cpp:827
mpc_local_planner::Controller::configureRobotDynamics
RobotDynamicsInterface::Ptr configureRobotDynamics(const ros::NodeHandle &nh)
Definition: controller.cpp:364
mpc_local_planner::Controller::_last_goal
teb_local_planner::PoseSE2 _last_goal
Definition: controller.h:176
obstacles.h
mpc_local_planner::Controller::_prefer_x_feedback
bool _prefer_x_feedback
Definition: controller.h:170
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
corbo::PredictiveController
t
geometry_msgs::TransformStamped t
mpc_local_planner::Controller
MPC controller for mobile robots.
Definition: controller.h:73
ros::NodeHandle
mpc_local_planner::RobotDynamicsInterface::Ptr
std::shared_ptr< RobotDynamicsInterface > Ptr
Definition: robot_dynamics_interface.h:89
ros::Subscriber
mpc_local_planner::Controller::_x_feedback_mutex
std::mutex _x_feedback_mutex
Definition: controller.h:172
mpc_local_planner::Controller::getInstance
corbo::ControllerInterface::Ptr getInstance() const override
Definition: controller.h:110
mpc_local_planner::Controller::_ocp_successful
bool _ocp_successful
Definition: controller.h:165
corbo::StructuredOptimalControlProblem::Ptr
std::shared_ptr< StructuredOptimalControlProblem > Ptr


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06