diff --git a/fuse_models/CMakeLists.txt b/fuse_models/CMakeLists.txt index dba1babd4..0df2d164d 100644 --- a/fuse_models/CMakeLists.txt +++ b/fuse_models/CMakeLists.txt @@ -55,9 +55,9 @@ add_library(${PROJECT_NAME} src/unicycle_2d.cpp src/unicycle_2d_ignition.cpp src/unicycle_2d_state_kinematic_constraint.cpp - src/unicycle_3d.cpp - src/unicycle_3d_ignition.cpp - src/unicycle_3d_state_kinematic_constraint.cpp + src/omnidirectional_3d.cpp + src/omnidirectional_3d_ignition.cpp + src/omnidirectional_3d_state_kinematic_constraint.cpp ) target_include_directories(${PROJECT_NAME} PUBLIC "$" diff --git a/fuse_models/fuse_plugins.xml b/fuse_models/fuse_plugins.xml index 4a8003d34..7830e9a81 100644 --- a/fuse_models/fuse_plugins.xml +++ b/fuse_models/fuse_plugins.xml @@ -12,13 +12,13 @@ - + A class that represents a kinematic constraint between 3D states at two different times. - + A fuse_models 3D kinematic model that generates kinematic constraints between provided time stamps, and adds those constraints to the fuse graph. @@ -101,9 +101,9 @@ A fuse_models ignition sensor designed to be used in conjunction with the unicycle 2D motion model. - + - A fuse_models ignition sensor designed to be used in conjunction with the unicycle 3D motion model. + A fuse_models ignition sensor designed to be used in conjunction with the Omnidirectional 3D motion model. diff --git a/fuse_models/include/fuse_models/odometry_3d_publisher.hpp b/fuse_models/include/fuse_models/odometry_3d_publisher.hpp index f69caae0f..f1c70f441 100644 --- a/fuse_models/include/fuse_models/odometry_3d_publisher.hpp +++ b/fuse_models/include/fuse_models/odometry_3d_publisher.hpp @@ -74,7 +74,7 @@ namespace fuse_models * the tf tree * - predict_to_current_time (bool, default: false) The tf publication happens at a fixed rate. * This parameter specifies whether we should - * predict, using the 3D unicycle model, the state + * predict, using the 3D omnidirectional model, the state * at the time of the tf publication, rather than * the last posterior (optimized) state. * - publish_frequency (double, default: 10.0) How often, in Hz, we publish the filtered state diff --git a/fuse_models/include/fuse_models/unicycle_3d.hpp b/fuse_models/include/fuse_models/omnidirectional_3d.hpp similarity index 97% rename from fuse_models/include/fuse_models/unicycle_3d.hpp rename to fuse_models/include/fuse_models/omnidirectional_3d.hpp index 0addd4070..f8e4ccab3 100644 --- a/fuse_models/include/fuse_models/unicycle_3d.hpp +++ b/fuse_models/include/fuse_models/omnidirectional_3d.hpp @@ -70,22 +70,22 @@ namespace fuse_models * x_vel, y_vel, z_vel, roll_vel, pitch_vel, yaw_vel, * x_acc, y_acc, z_acc). */ -class Unicycle3D : public fuse_core::AsyncMotionModel +class Omnidirectional3D : public fuse_core::AsyncMotionModel { public: - FUSE_SMART_PTR_DEFINITIONS_WITH_EIGEN(Unicycle3D) + FUSE_SMART_PTR_DEFINITIONS_WITH_EIGEN(Omnidirectional3D) /** * @brief Default constructor * * All plugins are required to have a constructor that accepts no arguments */ - Unicycle3D(); + Omnidirectional3D(); /** * @brief Destructor */ - ~Unicycle3D() = default; + ~Omnidirectional3D() = default; /** * @brief Shadowing extension to the AsyncMotionModel::initialize call @@ -237,7 +237,7 @@ class Unicycle3D : public fuse_core::AsyncMotionModel StateHistory state_history_; //!< History of optimized graph pose estimates }; -std::ostream & operator<<(std::ostream & stream, const Unicycle3D & unicycle_2d); +std::ostream & operator<<(std::ostream & stream, const Omnidirectional3D & unicycle_2d); } // namespace fuse_models diff --git a/fuse_models/include/fuse_models/unicycle_3d_ignition.hpp b/fuse_models/include/fuse_models/omnidirectional_3d_ignition.hpp similarity index 92% rename from fuse_models/include/fuse_models/unicycle_3d_ignition.hpp rename to fuse_models/include/fuse_models/omnidirectional_3d_ignition.hpp index 5dba3b875..ecbf39028 100644 --- a/fuse_models/include/fuse_models/unicycle_3d_ignition.hpp +++ b/fuse_models/include/fuse_models/omnidirectional_3d_ignition.hpp @@ -41,7 +41,7 @@ #include #include #include -#include +#include #include #include @@ -54,11 +54,11 @@ namespace fuse_models { /** - * @brief A fuse_models ignition sensor designed to be used in conjunction with the unicycle 3D + * @brief A fuse_models ignition sensor designed to be used in conjunction with the Omnidirectional 3D * motion model. * * This class publishes a transaction that contains a prior on each state subvariable used in the - * unicycle 3D motion model (x, y, z, qx, qy, qz, x_vel, y_vel, z_vel, roll_vel, pitch_vel, + * Omnidirectional 3D motion model (x, y, z, qx, qy, qz, x_vel, y_vel, z_vel, roll_vel, pitch_vel, * yaw_vel, x_acc, y_acc, z_acc). When the sensor is first loaded, it publishes a single transaction * with the configured initial state and covariance. * Additionally, whenever a pose is received, either on the set_pose service or the topic, this @@ -90,23 +90,23 @@ namespace fuse_models * - ~topic (string, default: "set_pose") The topic name for received PoseWithCovarianceStamped * messages */ -class Unicycle3DIgnition : public fuse_core::AsyncSensorModel +class Omnidirectional3DIgnition : public fuse_core::AsyncSensorModel { public: - FUSE_SMART_PTR_DEFINITIONS(Unicycle3DIgnition) - using ParameterType = parameters::Unicycle3DIgnitionParams; + FUSE_SMART_PTR_DEFINITIONS(Omnidirectional3DIgnition) + using ParameterType = parameters::Omnidirectional3DIgnitionParams; /** * @brief Default constructor * * All plugins are required to have a constructor that accepts no arguments */ - Unicycle3DIgnition(); + Omnidirectional3DIgnition(); /** * @brief Destructor */ - ~Unicycle3DIgnition() = default; + ~Omnidirectional3DIgnition() = default; /** * @brief Shadowing extension to the AsyncSensorModel::initialize call @@ -120,7 +120,7 @@ class Unicycle3DIgnition : public fuse_core::AsyncSensorModel * @brief Subscribe to the input topic to start sending transactions to the optimizer * * As a very special case, we are overriding the start() method instead of providing an onStart() - * implementation. This is because the Unicycle3DIgnition sensor calls reset() on the optimizer, + * implementation. This is because the Omnidirectional3DIgnition sensor calls reset() on the optimizer, * which in turn calls stop() and start(). If we used the AsyncSensorModel implementations of * start() and stop(), the system would hang inside of one callback function while waiting for * another callback to complete. @@ -131,7 +131,7 @@ class Unicycle3DIgnition : public fuse_core::AsyncSensorModel * @brief Unsubscribe from the input topic to stop sending transactions to the optimizer * * As a very special case, we are overriding the stop() method instead of providing an onStop() - * implementation. This is because the Unicycle3DIgnition sensor calls reset() on the optimizer, + * implementation. This is because the Omnidirectional3DIgnition sensor calls reset() on the optimizer, * which in turn calls stop() and start(). If we used the AsyncSensorModel implementations of * start() and stop(), the system would hang inside of one callback function while waiting for * another callback to complete. @@ -180,7 +180,7 @@ class Unicycle3DIgnition : public fuse_core::AsyncSensorModel /** * @brief Create and send a prior transaction based on the supplied pose * - * The unicycle 3d state members not included in the pose message (x_vel, y_vel, z_vel, roll_vel, pitch_vel, + * The omnidirectional 3d state members not included in the pose message (x_vel, y_vel, z_vel, roll_vel, pitch_vel, * yaw_vel, x_acc, y_acc, z_acc) will use the initial state values and standard deviations configured on the * parameter server. * diff --git a/fuse_models/include/fuse_models/unicycle_3d_predict.hpp b/fuse_models/include/fuse_models/omnidirectional_3d_predict.hpp similarity index 100% rename from fuse_models/include/fuse_models/unicycle_3d_predict.hpp rename to fuse_models/include/fuse_models/omnidirectional_3d_predict.hpp diff --git a/fuse_models/include/fuse_models/unicycle_3d_state_cost_function.hpp b/fuse_models/include/fuse_models/omnidirectional_3d_state_cost_function.hpp similarity index 97% rename from fuse_models/include/fuse_models/unicycle_3d_state_cost_function.hpp rename to fuse_models/include/fuse_models/omnidirectional_3d_state_cost_function.hpp index 29048e7ff..730d48def 100644 --- a/fuse_models/include/fuse_models/unicycle_3d_state_cost_function.hpp +++ b/fuse_models/include/fuse_models/omnidirectional_3d_state_cost_function.hpp @@ -36,7 +36,7 @@ #include -#include +#include #include #include @@ -84,7 +84,7 @@ namespace fuse_models * where, mu is a vector and S is a covariance matrix, then, A = S^{-1/2}, i.e the matrix A is the * square root information matrix (the inverse of the covariance). */ -class Unicycle3DStateCostFunction : public ceres::SizedCostFunction<15, 3, 4, 3, 3, 3, 3, 4, 3, 3, 3> +class Omnidirectional3DStateCostFunction : public ceres::SizedCostFunction<15, 3, 4, 3, 3, 3, 3, 4, 3, 3, 3> { public: FUSE_MAKE_ALIGNED_OPERATOR_NEW() @@ -97,7 +97,7 @@ class Unicycle3DStateCostFunction : public ceres::SizedCostFunction<15, 3, 4, 3, * order (x, y, z, roll, pitch, yaw, x_vel, y_vel, z_vel, roll_vel, pitch_vel, yaw_vel, * x_acc, y_acc, z_acc) */ - Unicycle3DStateCostFunction(const double dt, const fuse_core::Matrix15d & A); + Omnidirectional3DStateCostFunction(const double dt, const fuse_core::Matrix15d & A); /** * @brief Evaluate the cost function. Used by the Ceres optimization engine. @@ -279,7 +279,7 @@ class Unicycle3DStateCostFunction : public ceres::SizedCostFunction<15, 3, 4, 3, //!< information matrix }; -Unicycle3DStateCostFunction::Unicycle3DStateCostFunction( +Omnidirectional3DStateCostFunction::Omnidirectional3DStateCostFunction( const double dt, const fuse_core::Matrix15d & A) : dt_(dt), diff --git a/fuse_models/include/fuse_models/unicycle_3d_state_cost_functor.hpp b/fuse_models/include/fuse_models/omnidirectional_3d_state_cost_functor.hpp similarity index 96% rename from fuse_models/include/fuse_models/unicycle_3d_state_cost_functor.hpp rename to fuse_models/include/fuse_models/omnidirectional_3d_state_cost_functor.hpp index b632ecb44..d95523a01 100644 --- a/fuse_models/include/fuse_models/unicycle_3d_state_cost_functor.hpp +++ b/fuse_models/include/fuse_models/omnidirectional_3d_state_cost_functor.hpp @@ -34,7 +34,7 @@ #ifndef FUSE_MODELS__UNICYCLE_3D_STATE_COST_FUNCTOR_HPP_ #define FUSE_MODELS__UNICYCLE_3D_STATE_COST_FUNCTOR_HPP_ -#include +#include #include #include @@ -82,7 +82,7 @@ namespace fuse_models * where, mu is a vector and S is a covariance matrix, then, A = S^{-1/2}, i.e the matrix A is the * square root information matrix (the inverse of the covariance). */ -class Unicycle3DStateCostFunctor +class Omnidirectional3DStateCostFunctor { public: FUSE_MAKE_ALIGNED_OPERATOR_NEW() @@ -95,7 +95,7 @@ class Unicycle3DStateCostFunctor * order (x, y, z, qx, qy, qz, qw, x_vel, y_vel, z_vel, roll_vel, pitch_vel, yaw_vel, * x_acc, y_acc, z_acc) */ - Unicycle3DStateCostFunctor(const double dt, const fuse_core::Matrix15d & A); + Omnidirectional3DStateCostFunctor(const double dt, const fuse_core::Matrix15d & A); /** * @brief Evaluate the cost function. Used by the Ceres optimization engine. @@ -131,7 +131,7 @@ class Unicycle3DStateCostFunctor //!< information matrix }; -Unicycle3DStateCostFunctor::Unicycle3DStateCostFunctor( +Omnidirectional3DStateCostFunctor::Omnidirectional3DStateCostFunctor( const double dt, const fuse_core::Matrix15d & A) : dt_(dt), @@ -140,7 +140,7 @@ Unicycle3DStateCostFunctor::Unicycle3DStateCostFunctor( } template -bool Unicycle3DStateCostFunctor::operator()( +bool Omnidirectional3DStateCostFunctor::operator()( const T * const position1, const T * const orientation1, const T * const vel_linear1, diff --git a/fuse_models/include/fuse_models/unicycle_3d_state_kinematic_constraint.hpp b/fuse_models/include/fuse_models/omnidirectional_3d_state_kinematic_constraint.hpp similarity index 94% rename from fuse_models/include/fuse_models/unicycle_3d_state_kinematic_constraint.hpp rename to fuse_models/include/fuse_models/omnidirectional_3d_state_kinematic_constraint.hpp index e7d313a36..a61de7bab 100644 --- a/fuse_models/include/fuse_models/unicycle_3d_state_kinematic_constraint.hpp +++ b/fuse_models/include/fuse_models/omnidirectional_3d_state_kinematic_constraint.hpp @@ -63,15 +63,15 @@ namespace fuse_models * The fuse_models 3D state is a combination of 3D position, 3D orientation, 3D linear velocity, 3D * angular velocity, and 3D linear acceleration. */ -class Unicycle3DStateKinematicConstraint : public fuse_core::Constraint +class Omnidirectional3DStateKinematicConstraint : public fuse_core::Constraint { public: - FUSE_CONSTRAINT_DEFINITIONS_WITH_EIGEN(Unicycle3DStateKinematicConstraint) + FUSE_CONSTRAINT_DEFINITIONS_WITH_EIGEN(Omnidirectional3DStateKinematicConstraint) /** * @brief Default constructor */ - Unicycle3DStateKinematicConstraint() = default; + Omnidirectional3DStateKinematicConstraint() = default; /** * @brief Create a constraint using a time delta and a kinematic model cost functor @@ -94,7 +94,7 @@ class Unicycle3DStateKinematicConstraint : public fuse_core::Constraint * roll, pitch, yaw, x_vel, y_vel, z_vel, roll_vel, pitch_vel, yaw_vel, * x_acc, y_acc, z_acc) */ - Unicycle3DStateKinematicConstraint( + Omnidirectional3DStateKinematicConstraint( const std::string & source, const fuse_variables::Position3DStamped & position1, const fuse_variables::Orientation3DStamped & orientation1, @@ -111,7 +111,7 @@ class Unicycle3DStateKinematicConstraint : public fuse_core::Constraint /** * @brief Destructor */ - virtual ~Unicycle3DStateKinematicConstraint() = default; + virtual ~Omnidirectional3DStateKinematicConstraint() = default; /** * @brief Read-only access to the time delta between the first and second state (really, between @@ -183,6 +183,6 @@ class Unicycle3DStateKinematicConstraint : public fuse_core::Constraint } // namespace fuse_models -BOOST_CLASS_EXPORT_KEY(fuse_models::Unicycle3DStateKinematicConstraint); +BOOST_CLASS_EXPORT_KEY(fuse_models::Omnidirectional3DStateKinematicConstraint); #endif // FUSE_MODELS__UNICYCLE_3D_STATE_KINEMATIC_CONSTRAINT_HPP_ diff --git a/fuse_models/include/fuse_models/parameters/unicycle_3d_ignition_params.hpp b/fuse_models/include/fuse_models/parameters/omnidirectional_3d_ignition_params.hpp similarity index 98% rename from fuse_models/include/fuse_models/parameters/unicycle_3d_ignition_params.hpp rename to fuse_models/include/fuse_models/parameters/omnidirectional_3d_ignition_params.hpp index 8bf946f8d..053ac5572 100644 --- a/fuse_models/include/fuse_models/parameters/unicycle_3d_ignition_params.hpp +++ b/fuse_models/include/fuse_models/parameters/omnidirectional_3d_ignition_params.hpp @@ -52,9 +52,9 @@ namespace parameters { /** - * @brief Defines the set of parameters required by the Unicycle3DIgnition class + * @brief Defines the set of parameters required by the Omnidirectional3DIgnition class */ -struct Unicycle3DIgnitionParams : public ParameterBase +struct Omnidirectional3DIgnitionParams : public ParameterBase { public: /** diff --git a/fuse_models/src/odometry_3d_publisher.cpp b/fuse_models/src/odometry_3d_publisher.cpp index 48b6894dc..6fb94e5ee 100644 --- a/fuse_models/src/odometry_3d_publisher.cpp +++ b/fuse_models/src/odometry_3d_publisher.cpp @@ -47,7 +47,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/fuse_models/src/unicycle_3d.cpp b/fuse_models/src/omnidirectional_3d.cpp similarity index 95% rename from fuse_models/src/unicycle_3d.cpp rename to fuse_models/src/omnidirectional_3d.cpp index 6c6588811..92534d25d 100644 --- a/fuse_models/src/unicycle_3d.cpp +++ b/fuse_models/src/omnidirectional_3d.cpp @@ -47,9 +47,9 @@ #include #include #include -#include -#include -#include +#include +#include +#include #include #include #include @@ -60,7 +60,7 @@ #include // Register this motion model with ROS as a plugin. -PLUGINLIB_EXPORT_CLASS(fuse_models::Unicycle3D, fuse_core::MotionModel) +PLUGINLIB_EXPORT_CLASS(fuse_models::Omnidirectional3D, fuse_core::MotionModel) namespace std { @@ -117,16 +117,16 @@ inline void validateCovariance( namespace fuse_models { -Unicycle3D::Unicycle3D() +Omnidirectional3D::Omnidirectional3D() : fuse_core::AsyncMotionModel(1), // Thread count = 1 for local callback queue logger_(rclcpp::get_logger("uninitialized")), buffer_length_(rclcpp::Duration::max()), device_id_(fuse_core::uuid::NIL), - timestamp_manager_(&Unicycle3D::generateMotionModel, this, rclcpp::Duration::max()) + timestamp_manager_(&Omnidirectional3D::generateMotionModel, this, rclcpp::Duration::max()) { } -void Unicycle3D::print(std::ostream & stream) const +void Omnidirectional3D::print(std::ostream & stream) const { stream << "state history:\n"; for (const auto & state : state_history_) { @@ -135,7 +135,7 @@ void Unicycle3D::print(std::ostream & stream) const } } -void Unicycle3D::StateHistoryElement::print(std::ostream & stream) const +void Omnidirectional3D::StateHistoryElement::print(std::ostream & stream) const { stream << " position uuid: " << position_uuid << "\n" << " orientation uuid: " << orientation_uuid << "\n" @@ -149,7 +149,7 @@ void Unicycle3D::StateHistoryElement::print(std::ostream & stream) const << " acceleration linear: " << acc_linear << "\n"; } -void Unicycle3D::StateHistoryElement::validate() const +void Omnidirectional3D::StateHistoryElement::validate() const { if (!std::isfinite(position)) { throw std::runtime_error("Invalid position " + std::to_string(position)); @@ -168,7 +168,7 @@ void Unicycle3D::StateHistoryElement::validate() const } } -bool Unicycle3D::applyCallback(fuse_core::Transaction & transaction) +bool Omnidirectional3D::applyCallback(fuse_core::Transaction & transaction) { // Use the timestamp manager to generate just the required motion model segments. The timestamp // manager, in turn, makes calls to the generateMotionModel() function. @@ -184,12 +184,12 @@ bool Unicycle3D::applyCallback(fuse_core::Transaction & transaction) return true; } -void Unicycle3D::onGraphUpdate(fuse_core::Graph::ConstSharedPtr graph) +void Omnidirectional3D::onGraphUpdate(fuse_core::Graph::ConstSharedPtr graph) { updateStateHistoryEstimates(*graph, state_history_, buffer_length_); } -void Unicycle3D::initialize( +void Omnidirectional3D::initialize( fuse_core::node_interfaces::NodeInterfaces interfaces, const std::string & name) { @@ -197,7 +197,7 @@ void Unicycle3D::initialize( fuse_core::AsyncMotionModel::initialize(interfaces, name); } -void Unicycle3D::onInit() +void Omnidirectional3D::onInit() { logger_ = interfaces_.get_node_logging_interface()->get_logger(); clock_ = interfaces_.get_node_clock_interface()->get_clock(); @@ -264,13 +264,13 @@ void Unicycle3D::onInit() device_id_ = fuse_variables::loadDeviceId(interfaces_); } -void Unicycle3D::onStart() +void Omnidirectional3D::onStart() { timestamp_manager_.clear(); state_history_.clear(); } -void Unicycle3D::generateMotionModel( +void Omnidirectional3D::generateMotionModel( const rclcpp::Time & beginning_stamp, const rclcpp::Time & ending_stamp, std::vector & constraints, @@ -458,7 +458,7 @@ void Unicycle3D::generateMotionModel( } // Create the constraints for this motion model segment - auto constraint = fuse_models::Unicycle3DStateKinematicConstraint::make_shared( + auto constraint = fuse_models::Omnidirectional3DStateKinematicConstraint::make_shared( name(), *position1, *orientation1, @@ -486,7 +486,7 @@ void Unicycle3D::generateMotionModel( variables.push_back(acceleration_linear2); } -void Unicycle3D::updateStateHistoryEstimates( +void Omnidirectional3D::updateStateHistoryEstimates( const fuse_core::Graph & graph, StateHistory & state_history, const rclcpp::Duration & buffer_length) @@ -592,7 +592,7 @@ void Unicycle3D::updateStateHistoryEstimates( } } -void Unicycle3D::validateMotionModel( +void Omnidirectional3D::validateMotionModel( const StateHistoryElement & state1, const StateHistoryElement & state2, const fuse_core::Matrix15d & process_noise_covariance) { @@ -614,9 +614,9 @@ void Unicycle3D::validateMotionModel( } } -std::ostream & operator<<(std::ostream & stream, const Unicycle3D & unicycle_3d) +std::ostream & operator<<(std::ostream & stream, const Omnidirectional3D & omnidirectional_3d) { - unicycle_3d.print(stream); + omnidirectional_3d.print(stream); return stream; } diff --git a/fuse_models/src/unicycle_3d_ignition.cpp b/fuse_models/src/omnidirectional_3d_ignition.cpp similarity index 95% rename from fuse_models/src/unicycle_3d_ignition.cpp rename to fuse_models/src/omnidirectional_3d_ignition.cpp index 648c15b5c..d545007d0 100644 --- a/fuse_models/src/unicycle_3d_ignition.cpp +++ b/fuse_models/src/omnidirectional_3d_ignition.cpp @@ -46,7 +46,7 @@ #include #include #include -#include +#include #include #include #include @@ -61,12 +61,12 @@ #include // Register this motion model with ROS as a plugin. -PLUGINLIB_EXPORT_CLASS(fuse_models::Unicycle3DIgnition, fuse_core::SensorModel); +PLUGINLIB_EXPORT_CLASS(fuse_models::Omnidirectional3DIgnition, fuse_core::SensorModel); namespace fuse_models { -Unicycle3DIgnition::Unicycle3DIgnition() +Omnidirectional3DIgnition::Omnidirectional3DIgnition() : fuse_core::AsyncSensorModel(1), started_(false), initial_transaction_sent_(false), @@ -75,7 +75,7 @@ Unicycle3DIgnition::Unicycle3DIgnition() { } -void Unicycle3DIgnition::initialize( +void Omnidirectional3DIgnition::initialize( fuse_core::node_interfaces::NodeInterfaces interfaces, const std::string & name, fuse_core::TransactionCallback transaction_callback) @@ -84,7 +84,7 @@ void Unicycle3DIgnition::initialize( fuse_core::AsyncSensorModel::initialize(interfaces, name, transaction_callback); } -void Unicycle3DIgnition::onInit() +void Omnidirectional3DIgnition::onInit() { logger_ = interfaces_.get_node_logging_interface()->get_logger(); clock_ = interfaces_.get_node_clock_interface()->get_clock(); @@ -113,7 +113,7 @@ void Unicycle3DIgnition::onInit() interfaces_, params_.topic, params_.queue_size, - std::bind(&Unicycle3DIgnition::subscriberCallback, this, std::placeholders::_1), + std::bind(&Omnidirectional3DIgnition::subscriberCallback, this, std::placeholders::_1), sub_options ); @@ -124,7 +124,7 @@ void Unicycle3DIgnition::onInit() interfaces_.get_node_base_interface()->get_name(), params_.set_pose_service), std::bind( - &Unicycle3DIgnition::setPoseServiceCallback, this, std::placeholders::_1, + &Omnidirectional3DIgnition::setPoseServiceCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3), rclcpp::ServicesQoS(), cb_group_ @@ -136,14 +136,14 @@ void Unicycle3DIgnition::onInit() interfaces_.get_node_base_interface()->get_name(), params_.set_pose_deprecated_service), std::bind( - &Unicycle3DIgnition::setPoseDeprecatedServiceCallback, this, std::placeholders::_1, + &Omnidirectional3DIgnition::setPoseDeprecatedServiceCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3), rclcpp::ServicesQoS(), cb_group_ ); } -void Unicycle3DIgnition::start() +void Omnidirectional3DIgnition::start() { started_ = true; @@ -171,12 +171,12 @@ void Unicycle3DIgnition::start() } } -void Unicycle3DIgnition::stop() +void Omnidirectional3DIgnition::stop() { started_ = false; } -void Unicycle3DIgnition::subscriberCallback( +void Omnidirectional3DIgnition::subscriberCallback( const geometry_msgs::msg::PoseWithCovarianceStamped & msg) { try { @@ -186,7 +186,7 @@ void Unicycle3DIgnition::subscriberCallback( } } -bool Unicycle3DIgnition::setPoseServiceCallback( +bool Omnidirectional3DIgnition::setPoseServiceCallback( rclcpp::Service::SharedPtr service, std::shared_ptr request_id, const fuse_msgs::srv::SetPose::Request::SharedPtr req) @@ -209,7 +209,7 @@ bool Unicycle3DIgnition::setPoseServiceCallback( return true; } -bool Unicycle3DIgnition::setPoseDeprecatedServiceCallback( +bool Omnidirectional3DIgnition::setPoseDeprecatedServiceCallback( rclcpp::Service::SharedPtr service, std::shared_ptr request_id, const fuse_msgs::srv::SetPoseDeprecated::Request::SharedPtr req) @@ -229,7 +229,7 @@ bool Unicycle3DIgnition::setPoseDeprecatedServiceCallback( return true; } -void Unicycle3DIgnition::process( +void Omnidirectional3DIgnition::process( const geometry_msgs::msg::PoseWithCovarianceStamped & pose, std::function post_process) { // Verify we are in the correct state to process set pose requests @@ -329,7 +329,7 @@ void Unicycle3DIgnition::process( } } -void Unicycle3DIgnition::sendPrior(const geometry_msgs::msg::PoseWithCovarianceStamped & pose) +void Omnidirectional3DIgnition::sendPrior(const geometry_msgs::msg::PoseWithCovarianceStamped & pose) { const auto & stamp = pose.header.stamp; diff --git a/fuse_models/src/unicycle_3d_state_kinematic_constraint.cpp b/fuse_models/src/omnidirectional_3d_state_kinematic_constraint.cpp similarity index 83% rename from fuse_models/src/unicycle_3d_state_kinematic_constraint.cpp rename to fuse_models/src/omnidirectional_3d_state_kinematic_constraint.cpp index 0fe1f3a46..7caf9dc3b 100644 --- a/fuse_models/src/unicycle_3d_state_kinematic_constraint.cpp +++ b/fuse_models/src/omnidirectional_3d_state_kinematic_constraint.cpp @@ -36,8 +36,8 @@ #include #include -#include -#include +#include +#include #include #include #include @@ -48,7 +48,7 @@ namespace fuse_models { -Unicycle3DStateKinematicConstraint::Unicycle3DStateKinematicConstraint( +Omnidirectional3DStateKinematicConstraint::Omnidirectional3DStateKinematicConstraint( const std::string & source, const fuse_variables::Position3DStamped & position1, const fuse_variables::Orientation3DStamped & orientation1, @@ -78,7 +78,7 @@ Unicycle3DStateKinematicConstraint::Unicycle3DStateKinematicConstraint( { } -void Unicycle3DStateKinematicConstraint::print(std::ostream & stream) const +void Omnidirectional3DStateKinematicConstraint::print(std::ostream & stream) const { stream << type() << "\n" << " source: " << source() << "\n" @@ -97,21 +97,21 @@ void Unicycle3DStateKinematicConstraint::print(std::ostream & stream) const << " sqrt_info: " << sqrtInformation() << "\n"; } -ceres::CostFunction * Unicycle3DStateKinematicConstraint::costFunction() const +ceres::CostFunction * Omnidirectional3DStateKinematicConstraint::costFunction() const { - return new Unicycle3DStateCostFunction(dt_, sqrt_information_); + return new Omnidirectional3DStateCostFunction(dt_, sqrt_information_); // Here we return a cost function that computes the analytic derivatives/jacobians, but we could // use automatic differentiation as follows: // - // return new ceres::AutoDiffCostFunction( - // new Unicycle3DStateCostFunctor(dt_, sqrt_information_)); + // return new ceres::AutoDiffCostFunction( + // new Omnidirectional3DStateCostFunctor(dt_, sqrt_information_)); // And including the followings: // #include - // #include + // #include } } // namespace fuse_models -BOOST_CLASS_EXPORT_IMPLEMENT(fuse_models::Unicycle3DStateKinematicConstraint); -PLUGINLIB_EXPORT_CLASS(fuse_models::Unicycle3DStateKinematicConstraint, fuse_core::Constraint); +BOOST_CLASS_EXPORT_IMPLEMENT(fuse_models::Omnidirectional3DStateKinematicConstraint); +PLUGINLIB_EXPORT_CLASS(fuse_models::Omnidirectional3DStateKinematicConstraint, fuse_core::Constraint); diff --git a/fuse_models/test/CMakeLists.txt b/fuse_models/test/CMakeLists.txt index 15e15aad1..30602e78b 100644 --- a/fuse_models/test/CMakeLists.txt +++ b/fuse_models/test/CMakeLists.txt @@ -5,9 +5,9 @@ set(TEST_TARGETS test_unicycle_2d_state_cost_function test_graph_ignition test_unicycle_2d_ignition - test_unicycle_3d - test_unicycle_3d_predict - test_unicycle_3d_state_cost_function + test_omnidirectional_3d + test_omnidirectional_3d_predict + test_omnidirectional_3d_state_cost_function ) foreach(test_name ${TEST_TARGETS}) diff --git a/fuse_models/test/test_unicycle_3d.cpp b/fuse_models/test/test_omnidirectional_3d.cpp similarity index 95% rename from fuse_models/test/test_unicycle_3d.cpp rename to fuse_models/test/test_omnidirectional_3d.cpp index b8dfebfa9..f82bb75a2 100644 --- a/fuse_models/test/test_unicycle_3d.cpp +++ b/fuse_models/test/test_omnidirectional_3d.cpp @@ -6,7 +6,7 @@ #include #include -#include +#include #include #include #include @@ -18,15 +18,15 @@ /** * @brief Derived class used in unit tests to expose protected functions */ -class Unicycle3DModelTest : public fuse_models::Unicycle3D +class Omnidirectional3DModelTest : public fuse_models::Omnidirectional3D { public: - using fuse_models::Unicycle3D::updateStateHistoryEstimates; - using fuse_models::Unicycle3D::StateHistoryElement; - using fuse_models::Unicycle3D::StateHistory; + using fuse_models::Omnidirectional3D::updateStateHistoryEstimates; + using fuse_models::Omnidirectional3D::StateHistoryElement; + using fuse_models::Omnidirectional3D::StateHistory; }; -TEST(Unicycle3D, UpdateStateHistoryEstimates) +TEST(Omnidirectional3D, UpdateStateHistoryEstimates) { // Create some variables auto position1 = fuse_variables::Position3DStamped::make_shared(rclcpp::Time(1, 0)); @@ -155,10 +155,10 @@ TEST(Unicycle3D, UpdateStateHistoryEstimates) graph.addVariable(linear_acceleration4); // Add all of the variables to the state history - Unicycle3DModelTest::StateHistory state_history; + Omnidirectional3DModelTest::StateHistory state_history; state_history.emplace( position1->stamp(), - Unicycle3DModelTest::StateHistoryElement{ // NOLINT(whitespace/braces) + Omnidirectional3DModelTest::StateHistoryElement{ // NOLINT(whitespace/braces) position1->uuid(), orientation1->uuid(), linear_velocity1->uuid(), @@ -171,7 +171,7 @@ TEST(Unicycle3D, UpdateStateHistoryEstimates) fuse_core::Vector3d(0.0, 0.0, 0.0)}); // NOLINT(whitespace/braces) state_history.emplace( position2->stamp(), - Unicycle3DModelTest::StateHistoryElement{ // NOLINT(whitespace/braces) + Omnidirectional3DModelTest::StateHistoryElement{ // NOLINT(whitespace/braces) position2->uuid(), orientation2->uuid(), linear_velocity2->uuid(), @@ -184,7 +184,7 @@ TEST(Unicycle3D, UpdateStateHistoryEstimates) fuse_core::Vector3d(0.0, 0.0, 0.0)}); // NOLINT(whitespace/braces) state_history.emplace( position3->stamp(), - Unicycle3DModelTest::StateHistoryElement{ // NOLINT(whitespace/braces) + Omnidirectional3DModelTest::StateHistoryElement{ // NOLINT(whitespace/braces) position3->uuid(), orientation3->uuid(), linear_velocity3->uuid(), @@ -197,7 +197,7 @@ TEST(Unicycle3D, UpdateStateHistoryEstimates) fuse_core::Vector3d(0.0, 0.0, 0.0)}); // NOLINT(whitespace/braces) state_history.emplace( position4->stamp(), - Unicycle3DModelTest::StateHistoryElement{ // NOLINT(whitespace/braces) + Omnidirectional3DModelTest::StateHistoryElement{ // NOLINT(whitespace/braces) position4->uuid(), orientation4->uuid(), linear_velocity4->uuid(), @@ -210,7 +210,7 @@ TEST(Unicycle3D, UpdateStateHistoryEstimates) fuse_core::Vector3d(0.0, 0.0, 0.0)}); // NOLINT(whitespace/braces) state_history.emplace( position5->stamp(), - Unicycle3DModelTest::StateHistoryElement{ // NOLINT(whitespace/braces) + Omnidirectional3DModelTest::StateHistoryElement{ // NOLINT(whitespace/braces) position5->uuid(), orientation5->uuid(), linear_velocity5->uuid(), @@ -223,7 +223,7 @@ TEST(Unicycle3D, UpdateStateHistoryEstimates) fuse_core::Vector3d(0.0, 0.0, 0.0)}); // NOLINT(whitespace/braces) // Update the state history - Unicycle3DModelTest::updateStateHistoryEstimates( + Omnidirectional3DModelTest::updateStateHistoryEstimates( graph, state_history, rclcpp::Duration::from_seconds( 10.0)); diff --git a/fuse_models/test/test_unicycle_3d_predict.cpp b/fuse_models/test/test_omnidirectional_3d_predict.cpp similarity index 99% rename from fuse_models/test/test_unicycle_3d_predict.cpp rename to fuse_models/test/test_omnidirectional_3d_predict.cpp index 0b47a97c9..230c0b8cc 100644 --- a/fuse_models/test/test_unicycle_3d_predict.cpp +++ b/fuse_models/test/test_omnidirectional_3d_predict.cpp @@ -38,7 +38,7 @@ #include #include -#include +#include #include TEST(Predict, predictDirectVals) diff --git a/fuse_models/test/test_unicycle_3d_state_cost_function.cpp b/fuse_models/test/test_omnidirectional_3d_state_cost_function.cpp similarity index 93% rename from fuse_models/test/test_unicycle_3d_state_cost_function.cpp rename to fuse_models/test/test_omnidirectional_3d_state_cost_function.cpp index c0ce74508..bea153f97 100644 --- a/fuse_models/test/test_unicycle_3d_state_cost_function.cpp +++ b/fuse_models/test/test_omnidirectional_3d_state_cost_function.cpp @@ -41,8 +41,8 @@ #include #include -#include -#include +#include +#include TEST(CostFunction, evaluateCostFunction) { @@ -55,7 +55,7 @@ TEST(CostFunction, evaluateCostFunction) const double dt{0.1}; const fuse_core::Matrix15d sqrt_information{covariance.inverse().llt().matrixU()}; - const fuse_models::Unicycle3DStateCostFunction cost_function{dt, sqrt_information}; + const fuse_models::Omnidirectional3DStateCostFunction cost_function{dt, sqrt_information}; // Evaluate cost function const double position1[3] = {0.0, 0.0, 0.0}; @@ -120,8 +120,8 @@ TEST(CostFunction, evaluateCostFunction) // probe_results.error_log; // Create cost function using automatic differentiation on the cost functor - ceres::AutoDiffCostFunctioncost_function_autodiff(new fuse_models::Unicycle3DStateCostFunctor(dt, sqrt_information)); + ceres::AutoDiffCostFunctioncost_function_autodiff(new fuse_models::Omnidirectional3DStateCostFunctor(dt, sqrt_information)); // Evaluate cost function that uses automatic differentiation std::vector J_autodiff(num_parameter_blocks); std::vector jacobians_autodiff(num_parameter_blocks);