Skip to content
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

Add Boat Mission mode support through rate controllers #20082

Open
wants to merge 3 commits into
base: main
Choose a base branch
from

Conversation

Jaeyoung-Lim
Copy link
Member

@Jaeyoung-Lim Jaeyoung-Lim commented Aug 21, 2022

Describe problem solved by this pull request

Previously USVs(boats) did not work in mission mode due to the lack of low level control in the rover position control. Due to the low yaw damping on water the boat model would just oscillate on the yaw axis without meaningful navigation.

Describe your solution

This PR adds a rate control loop on the rover position control module and enables way point navigation for boats.

Test data / coverage

After PR

Tested in SITL and demonstrated successfully of following a survey pattern

make px4_sitl gazebo_boat
  • Flight log: Log
    image
    bokeh_plot (1)

Before PR

  • Flight log: Log
    image

Additional context

@Jaeyoung-Lim Jaeyoung-Lim added Rover 🚙 Rovers and other UGV Boat 🚤 labels Aug 21, 2022
@Jaeyoung-Lim Jaeyoung-Lim marked this pull request as ready for review August 21, 2022 14:02
@Jaeyoung-Lim Jaeyoung-Lim changed the title Boat Mission mode support through rate controllers Add Boat Mission mode support through rate controllers Aug 21, 2022
@Jaeyoung-Lim
Copy link
Member Author

Actuator controls seem to be saturating a lot...

bokeh_plot (2)

@Jaeyoung-Lim
Copy link
Member Author

Jaeyoung-Lim commented Aug 22, 2022

Retuned rate controller in last commit

image
image

param set-default GND_RATE_D 0.02
param set-default GND_RATE_FF 0.0
param set-default GND_RATE_I 0.0
param set-default GND_RATE_MAX 0.5
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shouldn't this be GND_YAW_RATE for readability? "ground rate" is very vague and could apply to all kinds of things, including being misinterpreted as speed IMO.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@jasta Thanks for the suggestion, and I agree that it would be a better naming. However, by using GND_YAW_RATE, parameters becomes too long (for example GND_YAW_RATE_IMAX ) and is not possible to add as a parameter

@jasta
Copy link
Contributor

jasta commented Aug 30, 2022

Thanks for doing this work, I was wondering why my USV was completing missions at such low speeds and it looks like it could be affected by the position controller issues you fixed in this PR. See attached actuator outputs if that's useful to confirm I'm seeing a similar issue:
bokeh_plot

Note that I also modified the navigator to support RTL mode by disabling the RTL_STATE_CLIMB state, I was hoping to prep a PR myself but got sidetracked trying to understand why the boat executed the RTL mode at such low speeds.

What are we missing with this PR to be able to merge it? Would it be useful if I help field test it?

@Jaeyoung-Lim
Copy link
Member Author

Jaeyoung-Lim commented Aug 30, 2022

@jasta Thanks!

Note that I also modified the navigator to support RTL mode by disabling the RTL_STATE_CLIMB state, I was hoping to prep a PR myself but got sidetracked trying to understand why the boat executed the RTL mode at such low speeds.

This would be awesome, and probably a much needed feature!

What are we missing with this PR to be able to merge it? Would it be useful if I help field test it?

What is missing is a field test on a real boat. I would say this is probably better than the previous state, but it would be great if you could give it a run and see if something critical is missing from this pull request.

Thanks!

@jasta
Copy link
Contributor

jasta commented Aug 30, 2022

I'll definitely give this a try, but after some further digging I realized existing parameters may have been the culprit in my case. Default GND_THR_MAX is 0.3f which seems to line up exactly with what the logs are saying. There are several parameters here that are interacting in ways that are very counter intuitive as well, even when looking at the code. For example, GND_SPEED_TRIM doesn't appear to trim the ground speed, but rather sets the target speed if the current setpoint doesn't specify a cruising speed? So if you set a mission cruise speed of 10m/s, but GND_SPEED_TRIM is 3m/s, you'll still get 10m/s? It also only applies if _control_mode.flag_control_position_enabled is true even though RoverPositionControl still may be in charge of setting speed/velocity?

Also, GND_SPEED_THR_SC is for some reason being read by navigator/rtl.cpp? Seems like dead code to me though??? Return mode seems to always publish setpoints with cruising_speed=-1 though, so that should let RoverPositionControl takeover and use appropriate values.

Oh, and I also seemed to have stumbled upon a bug where if you start a mission with a set cruising speed then issue a return command, then resume the mission, the mission speed will be set to cruising_speed=-1 again so you'll get GND_SPEED_TRIM most likely instead. If you change the mission value, re-upload it, then start the mission, this will be once again the mission speed.

@Jaeyoung-Lim
Copy link
Member Author

Jaeyoung-Lim commented Aug 30, 2022

There are several parameters here that are interacting in ways that are very counter intuitive as well, even when looking at the code. For example, GND_SPEED_TRIM doesn't appear to trim the ground speed, but rather sets the target speed if the current setpoint doesn't specify a cruising speed? So if you set a mission cruise speed of 10m/s, but GND_SPEED_TRIM is 3m/s, you'll still get 10m/s? It also only applies if _control_mode.flag_control_position_enabled is true even though RoverPositionControl still may be in charge of setting speed/velocity?

@jasta If you are curious, you can have a look at the logic:

float mission_target_speed = _param_gndspeed_trim.get();
if (PX4_ISFINITE(_pos_sp_triplet.current.cruising_speed) &&
_pos_sp_triplet.current.cruising_speed > 0.1f) {
mission_target_speed = _pos_sp_triplet.current.cruising_speed;
}
// Velocity in body frame
const Dcmf R_to_body(Quatf(_vehicle_att.q).inversed());
const Vector3f vel = R_to_body * Vector3f(ground_speed(0), ground_speed(1), ground_speed(2));
const float x_vel = vel(0);
const float x_acc = _vehicle_acceleration_sub.get().xyz[0];
// Compute airspeed control out and just scale it as a constant
mission_throttle = _param_throttle_speed_scaler.get()
* pid_calculate(&_speed_ctrl, mission_target_speed, x_vel, x_acc, dt);
// Constrain throttle between min and max
mission_throttle = math::constrain(mission_throttle, _param_throttle_min.get(), _param_throttle_max.get());

Although I would try to separate the discussion from this PR since it is not related.

Part of the reason is these things have been staying like this is because rovers were not being really tested/used in auto modes. Most rovers using PX4 were using offboard and direct actuator controls.

Therefore it would be great if we can address these problems one by one as we move forward. If you can address the points of the throttle control in a separate PR or at least post a issue would be helpful.

Also, GND_SPEED_THR_SC is for some reason being read by navigator/rtl.cpp? Seems like dead code to me though??? Return mode seems to always publish setpoints with cruising_speed=-1 though, so that should let RoverPositionControl takeover and use appropriate values.

Oh, and I also seemed to have stumbled upon a bug where if you start a mission with a set cruising speed then issue a return command, then resume the mission, the mission speed will be set to cruising_speed=-1 again so you'll get GND_SPEED_TRIM most likely instead. If you change the mission value, re-upload it, then start the mission, this will be once again the mission speed.

I think these are all related to the RTL use case, which was never really tested with boats and rovers. Therefore we would need to address these problems one by one - also not related to this PR and probably deserves a separate issue/PR

@jasta
Copy link
Contributor

jasta commented Aug 30, 2022

Ack'd, thanks for the quick info, I'm going to isolate all of these things and do some more field testing shortly. Hopefully I can provide an isolated report of the efficacy of just this diff once I correct for my baseline numbers with updated parameters.

@Jaeyoung-Lim
Copy link
Member Author

@jasta Would you have an ETA for the testing you mentioned? Thanks!

@junwoo091400
Copy link
Contributor

Rebased on main

Copy link
Contributor

@junwoo091400 junwoo091400 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Comments on quick points I discovered


_steering_input = math::constrain(_steering_input + torque(2), -1.0f, 1.0f);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shouldn't the steering input be set directly by the torque? Why would we accumulate the torque setpoint?

For example when we have achieved our desired rate, the FF gain will then still be accumulating in the steering input, which isn't what we want.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not really, the angular acceleration maps to the steering rate and not the steering input

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

How come it's the steering rate? When you want to apply certain torque, shouldn't the rudder deflection (steering) be proportional to that torque setpoint, instead of being integral of it?

Copy link
Member Author

@Jaeyoung-Lim Jaeyoung-Lim Sep 3, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If we assume $\dot{\psi} = V * \delta$ where $\delta$ is the steering and $\dot{\psi}$ is the yaw rate.

$\ddot{\psi} = \dot{V} * \delta + V * \dot{\delta}$
We are neglecting the effect of $\dot{V}$ here since we don't want to change $V$ to control the yaw rate. Therefore if we constraint $V$ to be constant,
$\ddot{\psi} \approx V * \dot{\delta}$

How come it's the steering rate? When you want to apply certain torque, shouldn't the rudder deflection (steering) be proportional to that torque setpoint, instead of being integral of it?

If rudder input directly corresponds to torque(or angular acceleration), with a given rudder and speed input you should have the yaw rate accelerating faster and faster. However, it normally converges quickly to a certain yaw rate.

This is assuming that you have sufficient yaw damping, which most rovers have. For boats I am not sure how well this assumption would hold, but guessing that it would be pretty good for differential thrust boats.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If we assume
ψ˙=V∗δ where δ is the steering and
ψ˙ is the yaw rate.

What does V stand for?

If rudder input directly corresponds to torque(or angular acceleration), with a given rudder and speed input you should have the yaw rate accelerating faster and faster. However, it normally converges quickly to a certain yaw rate.

Shouldn't this be handled by the I-term of the PID controller? Or, regarding the damping, is integrating the steering input the common way to mitigate this torque control problem?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What does V stand for?

V stands for velocity

Shouldn't this be handled by the I-term of the PID controller? Or, regarding the damping, is integrating the steering input the common way to mitigate this torque control problem?

I don't think it should be handled by the PID controller assuming steering corresponds to torque (because it does not)

Copy link
Member Author

@Jaeyoung-Lim Jaeyoung-Lim Sep 10, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@junwoo091400 If you think using a torque model is the right way, I am all open for it as long as you can show that it is a better way to handle rate control. 😄

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For now I have temporarily pushed this single commit to address this change I proposed, but we can revert back, if it proves to be inefficient, after real life testing of the vehicle: 205920e

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Comment on lines 326 to 322
///TODO: Max yaw rate
float desired_yaw_rate = _gnd_control.nav_lateral_acceleration_demand() / saturated_speed_2d.norm();
_rates_sp.roll = 0.0;
_rates_sp.pitch = 0.0;
_rates_sp.yaw = math::constrain(desired_yaw_rate, -max_yaw_rate, max_yaw_rate);
_rates_sp.thrust_body[0] = math::constrain(mission_throttle, 0.0f, 1.0f);
_rates_sp.timestamp = hrt_absolute_time();
_rates_sp_pub.publish(_rates_sp);
}
}
break;

case STOPPING: {
_act_controls.control[actuator_controls_s::INDEX_YAW] = 0.0f;
_act_controls.control[actuator_controls_s::INDEX_THROTTLE] = 0.0f;
_rates_sp.roll = 0.0;
_rates_sp.pitch = 0.0;
_rates_sp.yaw = 0.0;
_rates_sp.thrust_body[0] = 0.0;
_rates_sp.timestamp = hrt_absolute_time();
_rates_sp_pub.publish(_rates_sp);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We are publishing rate setpoint in 4 different positions in the code. Is this how we want to control / manipulate the _rates_sp variable? Was this unavoidable since the L1 controller's output must be translated into the rate setpoint?

Copy link
Member Author

@Jaeyoung-Lim Jaeyoung-Lim Sep 3, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No really, this is mainly because I wanted to add the rate controller first, and then later address the architectural issues in the rover controller in a different PR

@Jaeyoung-Lim
Copy link
Member Author

Rebased

@altmattr
Copy link

I'm in need of this excellent work, but I've hit a bug - can anyone here shed light on it? #20374

@Jaeyoung-Lim
Copy link
Member Author

@altmattr You would need this fix in the sitl_gazebo submodule: PX4/PX4-SITL_gazebo-classic#917

@altmattr
Copy link

@Jaeyoung-Lim Thankyou, that fix has worked for me. I am still unable to get a mission going. Missing upload keeps being rejected due to altitude too low. I'll keep working on it!

@Jaeyoung-Lim
Copy link
Member Author

@altmattr Try changing the altitude of your mission?

@junwoo091400 junwoo091400 added the Maintainers call Add items that should be discussed in the weekly maintainers call! label Aug 2, 2023
@Jaeyoung-Lim
Copy link
Member Author

@junwoo091400 I am against merging this without proper testing

@slgrobotics
Copy link
Contributor

Just to clarify - I brought up this PR to attention of the Team because I see the value of having a vehicle yaw controlled by the best generic mechanism available - RateControl module.

IMHO this is applicable to all ground vehicles, but there should be three distinct modules:

  1. An example small robotic Rover, like Avion R1. All that's needed here is a PID for speed/thrust control and a RateControl module for yaw/torque control - basically, just small touches to the existing RoverPositionControl
  2. Boat control module - to extend the above with boat-specific features.
  3. Large Rovers. In my case, I had not only to control speed and yaw as above, but divide vehicle path into phases - Turn, Departure, Line Following, Arrival, Stopping - and use a State Machine for that. It is working well for my gas engine driven zero turn mower, and might work for Ackermann-steered vehicles with significant inertia.

I don't have a boat, but I do have a mid-sized differential drive robot (14" wheels) to test case #1, and could probably have R1 rover fixed in classic Gazebo simulation.

My code is here, just in case: https://github.com/slgrobotics/PX4-Autopilot/tree/main/src/modules/rover_pos_control

@Jaeyoung-Lim
Copy link
Member Author

@slgrobotics Thanks for the context.

As you mentioned, this can also be tested on a rover. What I would like to see is what reasonable tuning values would be, and that it working properly without any major problems.

However, testing would need to be preceded before we get this PR in. I wouldn't feel comfortable merging something that is not tested and potentially promising.

@not7cd
Copy link

not7cd commented Aug 3, 2023

What would suffice as proper testing? My team might assist with that. We have an ASV and it was already running code from this PR during RoboBoat. But we didn't fully test PID parameters.

@Jaeyoung-Lim
Copy link
Member Author

Jaeyoung-Lim commented Aug 3, 2023

@not7cd

We have an ASV and it was already running code from this PR during RoboBoat.

Ha, interesting!

Great, a flight log from the following tests would fit into sufficient testing.

  • Drive in acro mode with step input on the yaw axis to see that the vehicle correctly stabilizes and maintains a constant yaw rate
  • Same test as above but on different speed to see that the PID adapts correctly to different speeds
  • Demonstration in mission mode where the vehicle tracks different waypoints

@Jaeyoung-Lim
Copy link
Member Author

@not7cd @slgrobotics Any updates?

@slgrobotics
Copy link
Contributor

@Jaeyoung-Lim - I've got my rover working just now, will be experimenting with your code tomorrow. Sorry for delay.

@slgrobotics
Copy link
Contributor

@Jaeyoung-Lim - It's a bit rainy here in Alabama and my progress is slow.

Here is what I have so far:

  1. My Rover requires some modifications, for which I have a fork from PX4 "main". To test this PR I copied its rover_pos_control folder over to mine. As this PR's origin is way outdated, it requires modifications to compile (see patch below). It makes sense to bring PR code to current "main" state.
  2. I am surprised to see GND_WHEEL_BASE gone, but looking at the code I see the reason. Will keep an eye on that.
  3. When I run the robot in Manual mode, it seems to be configured so that it doesn't move backwards, and stops only when I pull the stick all the way down. No big deal, but worth looking into that. Rovers and boats can be put in reverse.
  4. So far I could only test my Rover in a short mission. I had to set D=I=FF=0 and P=0.5 to avoid oscillations, that needs to be tuned. The robot seems to roughly move to a waypoint, but doesn't proceed to the next one. Obviously, lots of tuning to follow.

Here is what I did to make PR's code compile with current "main":

diff /home/sergei/src20/PX4-Autopilot/src/modules/rover_pos_control/./RoverPositionControl.cpp src/modules/rover_pos_control/./RoverPositionControl.cpp
96c96
< 		_gnd_control.set_l1_roll_limit(math::radians(0.0f));
---
> 		//_gnd_control.set_l1_roll_limit(math::radians(0.0f));
105c105
< 		_rate_control.setGains(matrix::Vector3f(0.0, 0.0, _param_rate_p.get()), matrix::Vector3f(0.0, 0.0, _param_rate_i.get()),
---
> 		_rate_control.setPidGains(matrix::Vector3f(0.0, 0.0, _param_rate_p.get()), matrix::Vector3f(0.0, 0.0, _param_rate_i.get()),
170,171d169
< 					_act_controls.control[actuator_controls_s::INDEX_ROLL] = 0.0f; // Nominally roll: _manual_control_setpoint.roll;
< 					_act_controls.control[actuator_controls_s::INDEX_PITCH] = 0.0f; // Nominally pitch: -_manual_control_setpoint.pitch;
173c171
< 					_act_controls.control[actuator_controls_s::INDEX_YAW] =
---
> 					_torque_control =
176c174
< 					_act_controls.control[actuator_controls_s::INDEX_THROTTLE] = (_manual_control_setpoint.throttle + 1.f) * .5f;
---
> 					_thrust_control = (_manual_control_setpoint.throttle + 1.f) * .5f;
384c382
< 		_act_controls.control[actuator_controls_s::INDEX_THROTTLE] = math::constrain(control_throttle, 0.0f, mission_throttle);
---
> 		_thrust_control = math::constrain(control_throttle, 0.0f, mission_throttle);
400c398
< 		_act_controls.control[actuator_controls_s::INDEX_YAW] = control_effort;
---
> 		_torque_control = control_effort;
404,405c402,403
< 		_act_controls.control[actuator_controls_s::INDEX_THROTTLE] = 0.0f;
< 		_act_controls.control[actuator_controls_s::INDEX_YAW] = 0.0f;
---
> 		_thrust_control = 0.0f;
> 		_torque_control = 0.0f;
447c445
< 	_act_controls.control[actuator_controls_s::INDEX_YAW] = _steering_input;
---
> 	_torque_control = _steering_input;
451c449
< 	_act_controls.control[actuator_controls_s::INDEX_THROTTLE] =  math::constrain(control_throttle, 0.0f, 1.0f);
---
> 	_thrust_control =  math::constrain(control_throttle, 0.0f, 1.0f);
568,569c566,567
< 			_act_controls.timestamp = hrt_absolute_time();
< 			_actuator_controls_pub.publish(_act_controls);
---
> 			//_act_controls.timestamp = hrt_absolute_time();
> 			//_actuator_controls_pub.publish(_act_controls);
573c571
< 			v_thrust_sp.xyz[0] = _act_controls.control[actuator_controls_s::INDEX_THROTTLE];
---
> 			v_thrust_sp.xyz[0] = _thrust_control;
580,582c578,580
< 			v_torque_sp.xyz[0] = _act_controls.control[actuator_controls_s::INDEX_ROLL];
< 			v_torque_sp.xyz[1] = _act_controls.control[actuator_controls_s::INDEX_PITCH];
< 			v_torque_sp.xyz[2] = _act_controls.control[actuator_controls_s::INDEX_YAW];
---
> 			v_torque_sp.xyz[0] = 0.0f;
> 			v_torque_sp.xyz[1] = 0.0f;
> 			v_torque_sp.xyz[2] = _torque_control;
diff /home/sergei/src20/PX4-Autopilot/src/modules/rover_pos_control/./RoverPositionControl.hpp src/modules/rover_pos_control/./RoverPositionControl.hpp
78d77
< #include <uORB/topics/actuator_controls.h>
115d113
< 	uORB::Publication<actuator_controls_s>		_actuator_controls_pub{ORB_ID(actuator_controls_0)};  /**< actuator controls publication */
133d130
< 	actuator_controls_s				_act_controls{};		/**< direct control of actuators */
161c158,160
< 	float _steering_input{0.0};
---
> 	float _steering_input{0.0f};
> 	float _torque_control{0.0f};
> 	float _thrust_control{0.0f};

@slgrobotics
Copy link
Contributor

slgrobotics commented Aug 14, 2023

@Jaeyoung-Lim - OK, I tried to run my rover under the PR code (adapted to current PX4 "main" state) and it didn't go well. I don't see any problem with the code itself - the rate controller worked fine, but the EKF2 heading was totally messed with my sensors (mpu9250+hmc5883) and the robot couldn't hold lines or follow waypoints. Things work better in sim, when I use "make gazebo-classic_r1_rover" build but replace R1 model with my own. EKF2has always been a problem for me, and on my big lawnmower I just use dual RTK GPS for heading directly to avoid such issues.

At the moment I can't be much help (although I might keep an eye on this) - so I hope there will be somebody else for testing.
My suggestion is to bring this PR up to date with "main" and keep trying.

BTW, the reverse not working issue will go away after line 148 is merged with "main" (no need for +1.f and *0.5f).

Dragger

@junwoo091400
Copy link
Contributor

robot couldn't hold lines or follow waypoints

Do you have a log to share? That would be helpful!

@slgrobotics
Copy link
Contributor

@Jaeyoung-Lim - I have log files, not sure if they are of any use. Normally I would make notes about conditions, reasoning and parameters, but these runs were very unsatisfactory - so I didn't get to that stage. I didn't really try to tune up the PIDs. Default P=5 caused gross oscillations.

https://review.px4.io/plot_app?log=ea472c57-9097-4034-930d-8d367850bcf7 (P=0.5)

https://review.px4.io/plot_app?log=b75f9566-43cc-452f-8d3b-5d3ef1543776 (P=0.1)

https://review.px4.io/plot_app?log=cbfe2842-8c9f-4487-b6e5-282722b17015

https://review.px4.io/plot_app?log=ed37a0a8-c7b2-41d1-beca-e4fd60865f87

I can run the beast again if you feel that would help.

@slgrobotics
Copy link
Contributor

@Jaeyoung-Lim - I tried to build the latest:
RoverPositionControl.cpp : 102 - should be setPidGains(...)
431 - should be _yaw_control = ... (act_controls deprecated)
435 - should be _throttle_control = ... - and maybe constrain to -1.0f +1.0f ?
builds ok after corrections above.

@slgrobotics
Copy link
Contributor

slgrobotics commented Aug 16, 2023

@Jaeyoung-Lim - I ran your latest code on my rover. This time I had a chance to play with parameters, and EKF2 was behaving reasonably well. My biggest problem was that with the speed controller delivering thrust values close to 1.0 the torque (yaw) values were added and actuators (wheels) were basically saturating. Robot refused to turn. Multicopter controller senses actuators saturation, and that could be done for diff drive rovers, if needed - but that's beyond the scope of this PR. I just trimmed the speed setpoint to a crawl to have it do the mission.

Here is the latest log - there is a lot more to tune though:

https://review.px4.io/plot_app?log=84ce4592-a79e-40ab-b9b3-dfdb3816d9eb

BTW, GND_ATT_P isn't used anymore

@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/vectored-thrust-for-surface-vessel-i/34920/2

@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/rc-speed-boat-with-px4-episode-1-using-px4-to-control-the-boat/28429/10

@hamishwillee
Copy link
Contributor

  1. Given this derives from rovers, would I be correct in saying Rovers don't support mission mode? What modes are supported? Just "manual" and "offboard"? Need to update https://docs.px4.io/main/en/frames_rover/ to say this.

@Jaeyoung-Lim
Copy link
Member Author

@hamishwillee Not really, when I was writing this, rover mission worked but failed on boars due to the low damping over water

@PyroX2
Copy link

PyroX2 commented Feb 10, 2024

@Jaeyoung-Lim Hi, we are using rover position control to control our custom ASV. We are currently at roboboat and we are trying to set waypoints based on position of buoys that camera sees. It seems to work on the ground but when we test it on water our ASV sometimes it swims to the side when it should forward. Could you suggest based on this log file if it is a problem with our ROS2 code or pixhawk configuration? Roboboat ends on sunday so we would be really grateful for any quick response. Thanks in advance
Log file: https://logs.px4.io/plot_app?log=991b55fe-7fea-471b-b77a-2353e4648201

cc @not7cd

@Jaeyoung-Lim
Copy link
Member Author

Jaeyoung-Lim commented Feb 10, 2024

@Kubol307 It is hard to know just looking at the log what your expectation is and how it is i plemented.

Have you tested the rate controller without your ros2 code? You need to isolate the two components so that you can identify where your problem actually is

@PyroX2
Copy link

PyroX2 commented Feb 10, 2024

@Jaeyoung-Lim We have just tested it on water and it's most likely a problem with our ROS2 code. When we are setting waypoints from QGC everything worked fine. However what's interesting is that when we tested it now everything worked fine until it started to swim in circles no matter what waypoints we send to it. Pixhawk reboot helped but it's not the first time it happened. The next time it occurs I will check if it's the same with waypoint from QGC. Here is the log file from this run: https://logs.px4.io/plot_app?log=e4226fff-58e4-4354-b27f-ab4b48fd8b33
And here spinning began:
Screenshot from 2024-02-10 09-09-57

@PyroX2
Copy link

PyroX2 commented Feb 10, 2024

And also our PID gains. Earlier, with higher P on rate controller we experienced really unstable movement. Setting it to about 0.05 helped a lot.
Screenshot from 2024-02-10 09-12-49

@Jaeyoung-Lim
Copy link
Member Author

@Kubol307 This PR implements a yaw rate controller. You need to check if the yaw rate controller is well tuned before analyzing position errors

@PyroX2
Copy link

PyroX2 commented Feb 10, 2024

@Jaeyoung-Lim What tests would help you to merge this pull request?

@Jaeyoung-Lim
Copy link
Member Author

@Kubol307 I am not sure how would merging this PR help you in the roboat competition?

If you want to hop on a call, I will be happy to help. You can reach out to me on the PX4 discord

@PyroX2
Copy link

PyroX2 commented Feb 11, 2024

@Jaeyoung-Lim Unfortunately we have already had our last run on roboboat. We might have found what was the problem as we found this issue: https://discuss.px4.io/t/rover-waypoint-altitude-issue/7455 Before we initialized pixhawk on the ground and then put the boat on water. Today we tried to push it a little into the water so that pixhawk initializes while being in lowest point and we didnt experienced the above issue. May the altitude actually be the problem? If you need any additional information I will be happy to provide you with that

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Boat 🚤 Maintainers call Add items that should be discussed in the weekly maintainers call! Rover 🚙 Rovers and other UGV
Projects
None yet
Development

Successfully merging this pull request may close these issues.

(Asking for Ideas) Exception for Non-aerial vehicle's takeoff altitude check for missions