-
Notifications
You must be signed in to change notification settings - Fork 201
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Bring MPC to the new flight stack #60
Conversation
…hod to use trajectory instead of point.
…e instead of break-routine
@@ -857,7 +878,7 @@ quadrotor_common::ControlCommand AutoPilot::start( | |||
} | |||
|
|||
if (timeInCurrentState() > optitrack_start_land_timeout_ | |||
|| reference_state_.position.z() >= optitrack_start_height_) | |||
|| state_estimate.position.z() >= optitrack_start_height_) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
why the change to state_estimate
from reference_state
?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Whats the intention behind checking what the reference height is? Doesn't it make more sense to check what your actual height is and cancel the take-off once you reached this height?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
if you look further in the function the reference is moved up and up as the loop is repeated. I would say that using the old method makes it more robust and smoother but this is only a feeling. By that I mean, hover WILL be reached even if you have an offset for idk which reason.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
So ideally the drone does what the reference tells it to, and in that case it does not make much of a difference. However, if e.g. the drone has a wrong thrust mapping and flies much lower than the reference, when using the state estimate, it will go up until it reached the start height (with a reference much higher) but then when it switches back to hover the reference is set to the current state estimate and the drone will drop by that much again which also does not result in the desired height. So by checking the reference height at least we get a smooth behavior in this case. Anyhow, if the drone does not follow the reference well it needs to be fixed...
Bottom line: I would change this back to reference state
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
There you go, the reason I was searching for! Make sense to me
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
OK, clarification:
When using the MPC, it lags behind since your take-off maneuver has a rising position, fixed velocity but zero acceleration and hover thrust, which is unfeasible at the beginning of the start maneuver.
This is no problem for feasible control with the MPC, but it means that the it lags behind due to the compromise of positon-, velocity-, acceleration- and thrust-error.
Possible solution:
- Ignore ~0.15m z-offset after start.
- Add a takeoff acceleration (which could be a parameter) at the beginning of the start maneuver.
|
||
reference_trajectory_ = quadrotor_common::Trajectory(); | ||
reference_trajectory_.trajectory_type = | ||
quadrotor_common::Trajectory::TrajectoryType::GENERAL; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
quick question, how about a constructor with the type as argument for the class quadrotor_common::Trajectory()
? to avoid code duplication. We could even have a constructor with one point as argument and automatically defined it as a general trajectory. It would make sense since we change the interface completely (i mean from point to trajectory in the run command...)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Agree! Will do it tomorrow!
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
also agree ;)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
done in uzh-rpg/rpg_quadrotor_common#11
quadrotor_common::ControlCommand AutoPilot::executeTrajectory( | ||
template <typename Tcontroller, typename Tparams> | ||
quadrotor_common::ControlCommand | ||
AutoPilot<Tcontroller, Tparams>::executeTrajectory( | ||
const quadrotor_common::QuadStateEstimate& state_estimate, | ||
ros::Duration* trajectory_execution_left_duration, |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
general comment: really, a pointer to a ros::Duration and int ?!? ---> how about a smart pointer?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
meh... lets make it pass-by-reference!
then there's no pointer magic but still avoiding copying, ok?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
No, it is our convention that arguments which are changed by the function are passed as pointers.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Conventions are here to be respected. Ok
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
agree, mark as done
|
||
std::list<quadrotor_common::TrajectoryPoint>::const_iterator it_points; | ||
std::list<quadrotor_common::Trajectory>::const_iterator it_trajectories; | ||
bool lookahead_reached(false); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
- could you comment the code, basic idea behind the heuristic (i'm lazy but so will be the next person working on it)
- should it not be a separate function like mpc?
- could we use specialization for these functions that change a lot ? I mean a definition for execute(mpc controller templated) and for execute(normal controller) ... Idk if it's possible but I think so. see here
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
3rd bullet: nope... if so we need to specify the template type in here... then we need the type at compile time.
but this is what we want to avoid, to be able to compile rpg_quadrotor_control without rpg_mpc.
I will think about making it more readable and understandable.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I will look at this in more detail later then
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@foehnph Agreed for the 3rd bullet, you are right!
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Ok temporary solution:
I commented the code there to make it understandable what it does.
I think this should be a separate class, like autopilot::Tracker
, the trajectory queue could be passed as reference and it can have time-based tracking and spacial tracking, as well as restrictions to forward-only tracking (can speed up iterations massively).
Additionally it could also handle the trajectory queue if wanted, but I guess it's easier to leave that in the autopilot.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
A bunch of comments but first of all thanks for this effort!
@@ -3,7 +3,8 @@ | |||
int main(int argc, char **argv) | |||
{ | |||
ros::init(argc, argv, "autopilot"); | |||
autopilot::AutoPilot autopilot; | |||
autopilot::AutoPilot<position_controller::PositionController, |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
also make the includes for the PositionController and PositionControllerParams in this file
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
done
@@ -228,3 +231,5 @@ class AutoPilot | |||
}; | |||
|
|||
} // namespace autopilot | |||
|
|||
#include "./autopilot_inl.h" |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
No newline at end of file
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
done
@@ -6,7 +6,7 @@ start_land_velocity: 0.5 # [m/s] | |||
start_idle_duration: 2.0 # [s] | |||
idle_thrust: 2.0 # [m/s] | |||
optitrack_start_height: 1.0 # [m] | |||
optitrack_start_land_timeout: 5 # [s] | |||
optitrack_start_land_timeout: 6 # [s] |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Why this this parameter change in this pull request?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
sorry was testing... undone
@@ -27,3 +27,4 @@ emergency_land_thrust: 9.0 # [m/s^2] | |||
|
|||
control_command_input_timeout: 0.1 # [s] | |||
enable_command_feedthrough: false | |||
predictive_control_lookahead: 2.0 # [s] |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
No newline at end of file
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
done
@@ -27,3 +27,4 @@ emergency_land_thrust: 9.0 # [m/s^2] | |||
|
|||
control_command_input_timeout: 0.1 # [s] | |||
enable_command_feedthrough: true | |||
predictive_control_lookahead: 2.0 # [s] |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
No new line at end of file
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
done
quadrotor_common::ControlCommand AutoPilot::executeTrajectory( | ||
template <typename Tcontroller, typename Tparams> | ||
quadrotor_common::ControlCommand | ||
AutoPilot<Tcontroller, Tparams>::executeTrajectory( | ||
const quadrotor_common::QuadStateEstimate& state_estimate, | ||
ros::Duration* trajectory_execution_left_duration, |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
No, it is our convention that arguments which are changed by the function are passed as pointers.
@@ -1147,20 +1222,57 @@ quadrotor_common::ControlCommand AutoPilot::executeTrajectory( | |||
*trajectory_execution_left_duration = ros::Duration(0.0); | |||
*trajectories_left_in_queue = 0; | |||
trajectory_queue_.pop_front(); | |||
setAutoPilotState(States::HOVER); | |||
return base_controller_.run(state_estimate, reference_state_, | |||
setAutoPilotStateForced(States::HOVER); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This should not be forced to avoid jumpy behavior if for whatever reason the trajectory ends with a non zero velocity. So by not forcing it will do a smooth breaking if necessary
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Yes but the you do not guarantee that you reach the end state...
the end of a trajectory normally has zero velocity ;-) and even if not it just means that you get to a stop with an offset where the velocity error is compensated by the position error.
I propose to change setAutoPilotStateForced()
so that it sets reference state velocity to zero when trigger to hover.
base_controller_params_); | ||
} | ||
else | ||
{ | ||
time_start_trajectory_execution_ += | ||
trajectory_queue_.front().points.back().time_from_start; | ||
trajectory_queue_.front().points.back().time_from_start; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I saw a few of those... Detail but this is just a thing because of non equal auto formatting which doesn't hurt but is also not necessary.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
we use two spaces for tabs... so if I see it I change it :-)
|
||
std::list<quadrotor_common::TrajectoryPoint>::const_iterator it_points; | ||
std::list<quadrotor_common::Trajectory>::const_iterator it_trajectories; | ||
bool lookahead_reached(false); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I will look at this in more detail later then
@@ -137,10 +138,11 @@ class AutoPilot | |||
|
|||
state_predictor::StatePredictor state_predictor_; | |||
|
|||
position_controller::PositionController base_controller_; | |||
position_controller::PositionControllerParams base_controller_params_; | |||
Tcontroller base_controller_; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I named this base controller because I thought that there might be new controllers that are only used for certain tasks but some of the basic tasks are always executed with the base controller (like start land etc.). @foehnph would something like this make sense (and then have two controller instances) or not?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I agree with @mfaessle, it makes it easier for you @foehnph since you don't need to implement the velocity mode in mpc, no?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
not really... then you would have to switch between controllers, implement state machine for that and generally reimplement a shitload of things if you want to use the autopilot with the new controller and not just have a different controller in feedthrough...
About transforming the cpp file into a header... I never used templates myself but maybe @tcies has some comments about naming conventions etc of such files. |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
See new comments
updated rpg_quadrotor_common with new Trajectory constructor, so... |
can someone approve this please? |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
lgtm
@@ -877,16 +899,27 @@ quadrotor_common::ControlCommand AutoPilot::start( | |||
+ start_land_velocity_ | |||
* (timeInCurrentState() - start_idle_duration_); | |||
reference_state_.velocity.z() = start_land_velocity_; | |||
if(timeInCurrentState() < start_idle_duration_ + |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This is a hack since the velocity does not change with acceleration over time. But as long as it works for both controllers I can live with it ;) The nicest way would be if it would be a real trapezoidal velocity profile during the start maneuver.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I'm gonna change that, test in simulation and request an approve again
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I opened an issue regarding this (#64). Feel free to adress it in a new pull request.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
already done here
@@ -877,16 +899,29 @@ quadrotor_common::ControlCommand AutoPilot::start( | |||
+ start_land_velocity_ | |||
* (timeInCurrentState() - start_idle_duration_); | |||
reference_state_.velocity.z() = start_land_velocity_; | |||
if(timeInCurrentState() < start_idle_duration_ + | |||
start_land_velocity_/start_land_acceleration_) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
spaces around arithmetic symbols please
finally happy? I'll merge tomorrow morning... ;-) |
I made some changes to allow compatibility with our new MPC.
It includes mainly templating the autopilot on the controller type and parameter type, which requires the autopilot.cpp to move to the header file, solved as a head include.
Further changes were also mentioned in #5 and we concluded that references are always given in the form of a
Trajectory
(and no longerTrajectoryPoint
) to the controller.The position controller would then just take the first point in it, while the MPC can use the first (for a single reference) or a whole lookahead on a trajectory.
I made several changes and would be happy to hear your comments.
@Internals: also take a look at: uzh-rpg/rpg_mpc#5