Skip to content

Henrik/velocity/merge#697

Open
Henrimha wants to merge 141 commits into
mainfrom
Henrik/velocity/merge
Open

Henrik/velocity/merge#697
Henrimha wants to merge 141 commits into
mainfrom
Henrik/velocity/merge

Conversation

@Henrimha
Copy link
Copy Markdown

Implemented a 3-DOF velocity controller, with a PID and LQR controller that can be set at launch.

Henrimha and others added 30 commits September 24, 2025 13:41
Copy link
Copy Markdown
Contributor

@Q3rkses Q3rkses left a comment

Choose a reason for hiding this comment

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

Dont upload LOS guidance for your PR review.

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

Dont upload cache files

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

remove anbits files so i can focus on your review

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

still not your change

@Q3rkses
Copy link
Copy Markdown
Contributor

Q3rkses commented Mar 28, 2026

Rerequest review when only files you want me to review are in the PR

@jorgenfj jorgenfj mentioned this pull request Mar 28, 2026
@Henrimha Henrimha requested a review from Q3rkses March 29, 2026 15:44
Copy link
Copy Markdown
Contributor

@Q3rkses Q3rkses left a comment

Choose a reason for hiding this comment

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

Good start, once implemented all changes ask for re-review

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

still not your change

Comment on lines +12 to +13
dampening_matrix_low: [23.0,0.0,0.0,0.0,0.0,0.0, 0.0,46.0,0.0,0.0,0.0,0.0, 0.0,0.0,46.0,0.0,0.0,0.0, 0.0,0.0,0.0,46.0,0.0,0.0, 0.0,0.0,0.0,0.0,46.0,0.0, 0.0,0.0,0.0,0.0,0.0,46.0]
dampening_matrix_high: [1.0,0.0,0.0,0.0,0.0,0.0, 0.0,1.0,0.0,0.0,0.0,0.0, 0.0,0.0,1.0,0.0,0.0,0.0, 0.0,0.0,0.0,1.0,0.0,0.0, 0.0,0.0,0.0,0.0,1.0,0.0, 0.0,0.0,0.0,0.0,0.0,1.0]
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

why are these alone under ros params and not under some informative header or in drone.yaml in the auv_setup if they are specific to a drone

Comment on lines +12 to +13
dampening_matrix_low: [23.0,0.0,0.0,0.0,0.0,0.0, 0.0,46.0,0.0,0.0,0.0,0.0, 0.0,0.0,46.0,0.0,0.0,0.0, 0.0,0.0,0.0,46.0,0.0,0.0, 0.0,0.0,0.0,0.0,46.0,0.0, 0.0,0.0,0.0,0.0,0.0,46.0]
dampening_matrix_high: [1.0,0.0,0.0,0.0,0.0,0.0, 0.0,1.0,0.0,0.0,0.0,0.0, 0.0,0.0,1.0,0.0,0.0,0.0, 0.0,0.0,0.0,1.0,0.0,0.0, 0.0,0.0,0.0,0.0,1.0,0.0, 0.0,0.0,0.0,0.0,0.0,1.0]
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

same here

Comment thread control/velocity_controller/include/tests/test_VC.hpp Outdated
Comment on lines +10 to +21
class LQRController {
public:
LQRController();
bool set_matrices(std::vector<double> Q_,
std::vector<double> R_,
std::vector<double> inertia_matrix,
double max_force,
std::vector<double> D_low);
void reset_controller(int nr = 0);
bool calculate_thrust(State states, Guidance_data guidance_values);
bool set_interval(double interval);
Eigen::Vector<double, 3> get_thrust();
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

It is important to document what your classes and functions do in HPP files. They are the entry points to your code.

follow a structured guideline for examples look at the hpp files in thrust_allocator_auv

Something like this https://cppscripts.com/cpp-docstrings, i dont really care about the doxygen part personally but i like the on hover description and, it being easy to read IO params

Suggested change
class LQRController {
public:
LQRController();
bool set_matrices(std::vector<double> Q_,
std::vector<double> R_,
std::vector<double> inertia_matrix,
double max_force,
std::vector<double> D_low);
void reset_controller(int nr = 0);
bool calculate_thrust(State states, Guidance_data guidance_values);
bool set_interval(double interval);
Eigen::Vector<double, 3> get_thrust();
/**
* @brief the LQRController class declares and groups all parameters the LQR controller will utilize and
* exposes the calculate_thrust_method which will be used in the main loop to calculate the input u.
*/
class LQRController {
public:
LQRController();
/**
* @brief set_matrices() will take all matrices necessary for the LQR controller to function and set
* them as member variables of the class.
* @param Q_ the matrix containing weights for the different states in the LQR objective function
* @param R_ the matrix containing weights for the inputs, used in the LQR objective function
.
.
.
*/
bool set_matrices(std::vector<double> Q_,
std::vector<double> R_,
std::vector<double> inertia_matrix,
double max_force,
std::vector<double> D_low);
.
.
.

you get the idea.

Comment on lines +59 to +60
| `inertia_matrix` | `double[]` | 36 | Row-major 6x6 rigid body inertia matrix |
| `dampening_matrix_low` | `double[]` | 36 | Row-major 6x6 hydrodynamic damping matrix at low speed |
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

give dimention, size is eh

Comment on lines +128 to +130
The system matrix `A` is re-linearized around the current state every control timestep. Guidance references in NED are converted to body-frame errors using the rotation matrix method before being passed to the controller — not by angle subtraction.

The gain `K` is computed by solving the continuous-time algebraic Riccati equation via `ct::optcon::LQR`. The control law is:
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

perhaps give me the DLQR equation here

Comment thread .gitignore
msg/_*.py
build_isolated/
devel_isolated/
*.cache/
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

bruh

Comment thread .gitignore Outdated
# Emacs
.#*

.cache
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

bruh ^

Comment thread .ignore Outdated
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

huh why did you rename this file and what is a .ignore

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

5 participants