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

Expose Ceres Solver, Problem and Covariance Options as ROS parameters #78

Conversation

efernandez
Copy link
Collaborator

@efernandez efernandez commented Jul 16, 2019

This allows to set all ceres::Solver::Options, ceres::Problem::Options and ceres::Covariance::Options using ROS parameters.

The motivation is to tune the solver and problem for better performance or accuracy, after looking at the tuning results shown in the plots at https://github.com/SteveMacenski/slam_toolbox , which was shared with me by @svwilliams . Unfortunately, it looks like the best configuration is almost the same as the default one 😆 , except for the preconditioner_type option, which defaults to JACOBI but it's set to SCHUR_JACOBI, which indeed make things a little faster for me (from 55 to 49% CPU with my fuse_rl configuration).

Either way, I think this is useful to tune things with other goals in mind, like accuracy, debugging, and still performance. TBH I haven't played a lot with the options/parameters, other than confirming things are being set and used internally.

I also suspect the enable_fast_removal option doesn't make a big different for the ceres::Problem because I think it's built from scratch every time.

I took the list of options from the latest version of Ceres, which will be 2.0.0, but also supported 1.13.x:

@@ -58,7 +58,7 @@
#include <memory>
#include <string>

// Required by make_aligned_shared, that uses Eigen::aligned_allocator<T>().
// Required by __MAKE_SHARED_ALIGNED_DEFINITION, that uses Eigen::aligned_allocator<T>().
Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Simply updating the comment, because we finally don't use make_aligned_shared, which doesn't exist.

*
* @param[in] node_handle - The node handle used to load the parameter
* @param[in] parameter_name - The parameter name to load
* @param[in] default_value - A default value to use if the provided parameter name does not exist
* @return The loaded (or default) value
*/
double getPositiveParam(const ros::NodeHandle& node_handle, const std::string& parameter_name, double default_value)
Copy link
Collaborator Author

Choose a reason for hiding this comment

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

At the end I don't really use getPositiveParam for integral types, but I think this change is for good, although it'd be great to have this function in a more generic place. Either way, if you don't like this, it's in its own commit, so it's easy drop it from this PR.

@efernandez efernandez force-pushed the CORE-13949-expose-ceres-solver-and-problem-options-as-ros-params branch from 0ed3490 to c2949ba Compare July 19, 2019 08:02
@svwilliams
Copy link
Contributor

Sorry it is taking me so long to go through this one. I will eventually get some version of this merged, hopefully next week. It was on my ToDo list to support setting Ceres parameters, so thanks for beating me to it.

@efernandez
Copy link
Collaborator Author

efernandez commented Jul 25, 2019

I'd check the continuous integration results to fix whatever is failing (likely roslint issues), but I'm afraid this is requesting me too much: 🤔

Screenshot from 2019-07-25 19-53-33

I'm not 100% sure if that will grant it access to the organizations I'm in, but I wonder why is that needed or what it actually does.

@efernandez efernandez force-pushed the CORE-13949-expose-ceres-solver-and-problem-options-as-ros-params branch from c2949ba to ef1180f Compare July 25, 2019 18:52
@efernandez
Copy link
Collaborator Author

There shouldn't be any roslint issues now.

@efernandez efernandez force-pushed the CORE-13949-expose-ceres-solver-and-problem-options-as-ros-params branch from ef1180f to 96c8e41 Compare August 14, 2019 16:53
@efernandez
Copy link
Collaborator Author

I've just rebased this PR and added the changes from locusrobotics/fuse_rl#22 here.

FYI @ayrton04 @svwilliams

@SteveMacenski
Copy link

@efernandez on your slam toolbox link, trust me the fact that nearly the defaults were the best is not lost on me. I probably spent 2 weeks thinking how much smarter I was than the Ceres guys trying out combinations to come crawling back. I learned alot so shrug.

Anyhow reason I comment- there are some parameters I did not include as a "don't give them enough rope to hang themselves" I see that you've exposed parameters for both line search and trust region strategies, which for most applications (at least I'm imagining this being used for) line search seems to be a bad choice, and many of the parameters only do things in certain modes. Removing those would simplify the overwhelming number of choices to the things that people will actually want to focus in on.

@efernandez
Copy link
Collaborator Author

efernandez commented Aug 15, 2019

Thanks for you comment @SteveMacenski . I really appreciate your effort to analyse the different options. It's a shame though that defaults are almost the best combination, except fo the pre-conditioner, which is actually slightly faster with SCHUR_JACOBI. 👍

I decided to expose all options because I don't know if someone wants to play with any of them, but you're right that some options are only used for certain types of solvers. I'm happy to drop some options if that's always the case, or document which options are the most relevant ones. That way it'd be clear to the user what options are those by just looking at this package, although ceres already does a good job at documenting all options. 😃

@SteveMacenski
Copy link

@efernandez fair enough -- just thought I'd mention it. I'm always a fan of giving every single little dial they can turn, and especially since this is supposed to be general, it makes sense. I looked at the structure and think "huh this really seems designed towards localization/slam/filtering" which fit trust region over line search categorically so there's an opportunity to simplify since about 50% of the parameters don't do anything in trust region.

If nothing else Ceres docs exist and this thread 👍

@efernandez
Copy link
Collaborator Author

Not sure why the checks failed. I've rebased this on top of devel and run make roslint on all pkgs changed, and everything LGTM locally. Could you tell me what checks ares failing, please?

@svwilliams
Copy link
Contributor

This is for the Xenial build. There were no errors in the Bionic build.

/home/ec2-user/workspace/test_rosdistro_fuse_PR-78/package/fuse_models/include/fuse_models/parameters/odometry_2d_publisher_params.h:135:26: error: ‘struct ceres::Covariance::Options’ has no member named ‘sparse_linear_algebra_library_type’

[2019-08-14T16:56:49.923Z]        covariance_options.sparse_linear_algebra_library_type = fuse_core::getParam(

I'm guessing the default version of Ceres in Xenial doesn't have that parameter?

@efernandez efernandez force-pushed the CORE-13949-expose-ceres-solver-and-problem-options-as-ros-params branch from 96c8e41 to cde1523 Compare August 23, 2019 10:25
@efernandez
Copy link
Collaborator Author

Thanks @svwilliams . I just fixed it. The sparse_linear_algebra_library_type options was added to ceres::Covariance::Options in version 1.13.0, so Ubuntu Xenial must be using and older version.

This commit introduced that changed: ceres-solver/ceres-solver@14d8297 (also mentioned in the code now)

@efernandez efernandez changed the title Expose Ceres Solver and Problem Options as ROS parameters Expose Ceres Solver, Problem and Covariance Options as ROS parameters Aug 23, 2019
Copy link
Contributor

@svwilliams svwilliams left a comment

Choose a reason for hiding this comment

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

Sorry this took so long to approve. And what I wouldn't give for a Ceres-maintained INI file reader.

ros::NodeHandle private_node_handle("~");
fuse_graphs::HashGraphParams hash_graph_params;
hash_graph_params.loadFromROS(private_node_handle);
fuse_optimizers::FixedLagSmoother optimizer(fuse_graphs::HashGraph::make_unique(hash_graph_params.problem_options));
Copy link
Contributor

Choose a reason for hiding this comment

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

Since you made a HashGraphParams object, it would probably make sense to pass the whole struct to the HashGraph constructor, rather than just the problem_options field.

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Makes sense. Done.

@@ -0,0 +1,188 @@
/***************************************************************************
* Copyright (C) 2019 Clearpath Robotics. All rights reserved.
Copy link
Contributor

Choose a reason for hiding this comment

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

This license is probably going to have to change.

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

No problem. Would you guys change it before merging?

namespace ceres
{

bool StringtoLoggingType(std::string value, LoggingType* type)
Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Oops, it looks like I have this the other way around. Fixing it.

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Fixed.

@efernandez efernandez force-pushed the CORE-13949-expose-ceres-solver-and-problem-options-as-ros-params branch 2 times, most recently from d337a74 to a5d4b0e Compare August 30, 2019 15:56
refs CORE-13949

It accepts integral and floating point types only.
That use Eigen::aligned_allocator
refs CORE-13949

Instead of ceres::Problem::Options directly.
@efernandez efernandez force-pushed the CORE-13949-expose-ceres-solver-and-problem-options-as-ros-params branch from a5d4b0e to e850e5e Compare August 30, 2019 15:59
@svwilliams svwilliams merged commit 7d6c005 into locusrobotics:devel Aug 30, 2019
@efernandez
Copy link
Collaborator Author

Thanks, I just realized I removed the serialization headers by mistake while solving some conflicts after rebasing. 😃

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

Successfully merging this pull request may close these issues.

None yet

4 participants