Skip to content

Commit

Permalink
rename unicycle3d to omnidirectional3d
Browse files Browse the repository at this point in the history
  • Loading branch information
giafranchini committed Jan 11, 2024
1 parent 0515c90 commit 72ff6a9
Show file tree
Hide file tree
Showing 18 changed files with 110 additions and 110 deletions.
6 changes: 3 additions & 3 deletions fuse_models/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
Expand Down
8 changes: 4 additions & 4 deletions fuse_models/fuse_plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
</description>
</class>

<class type="fuse_models::Unicycle3DStateKinematicConstraint" base_class_type="fuse_core::Constraint">
<class type="fuse_models::Omnidirectional3DStateKinematicConstraint" base_class_type="fuse_core::Constraint">
<description>
A class that represents a kinematic constraint between 3D states at two different times.
</description>
</class>

<class type="fuse_models::Unicycle3D" base_class_type="fuse_core::MotionModel">
<class type="fuse_models::Omnidirectional3D" base_class_type="fuse_core::MotionModel">
<description>
A fuse_models 3D kinematic model that generates kinematic constraints between provided time stamps, and adds
those constraints to the fuse graph.
Expand Down Expand Up @@ -101,9 +101,9 @@
A fuse_models ignition sensor designed to be used in conjunction with the unicycle 2D motion model.
</description>
</class>
<class type="fuse_models::Unicycle3DIgnition" base_class_type="fuse_core::SensorModel">
<class type="fuse_models::Omnidirectional3DIgnition" base_class_type="fuse_core::SensorModel">
<description>
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.
</description>
</class>
</library>
2 changes: 1 addition & 1 deletion fuse_models/include/fuse_models/odometry_3d_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
#include <fuse_core/async_sensor_model.hpp>
#include <fuse_core/fuse_macros.hpp>
#include <fuse_core/uuid.hpp>
#include <fuse_models/parameters/unicycle_3d_ignition_params.hpp>
#include <fuse_models/parameters/omnidirectional_3d_ignition_params.hpp>
#include <fuse_msgs/srv/set_pose.hpp>
#include <fuse_msgs/srv/set_pose_deprecated.hpp>

Expand All @@ -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
Expand Down Expand Up @@ -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
Expand All @@ -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.
Expand All @@ -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.
Expand Down Expand Up @@ -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.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

#include <ceres/sized_cost_function.h>

#include <fuse_models/unicycle_3d_predict.hpp>
#include <fuse_models/omnidirectional_3d_predict.hpp>

#include <fuse_core/eigen.hpp>
#include <fuse_core/fuse_macros.hpp>
Expand Down Expand Up @@ -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()
Expand All @@ -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.
Expand Down Expand Up @@ -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),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#ifndef FUSE_MODELS__UNICYCLE_3D_STATE_COST_FUNCTOR_HPP_
#define FUSE_MODELS__UNICYCLE_3D_STATE_COST_FUNCTOR_HPP_

#include <fuse_models/unicycle_3d_predict.hpp>
#include <fuse_models/omnidirectional_3d_predict.hpp>

#include <fuse_core/eigen.hpp>
#include <fuse_core/fuse_macros.hpp>
Expand Down Expand Up @@ -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()
Expand All @@ -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.
Expand Down Expand Up @@ -131,7 +131,7 @@ class Unicycle3DStateCostFunctor
//!< information matrix
};

Unicycle3DStateCostFunctor::Unicycle3DStateCostFunctor(
Omnidirectional3DStateCostFunctor::Omnidirectional3DStateCostFunctor(
const double dt,
const fuse_core::Matrix15d & A)
: dt_(dt),
Expand All @@ -140,7 +140,7 @@ Unicycle3DStateCostFunctor::Unicycle3DStateCostFunctor(
}

template<typename T>
bool Unicycle3DStateCostFunctor::operator()(
bool Omnidirectional3DStateCostFunctor::operator()(
const T * const position1,
const T * const orientation1,
const T * const vel_linear1,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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,
Expand All @@ -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
Expand Down Expand Up @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -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:
/**
Expand Down
2 changes: 1 addition & 1 deletion fuse_models/src/odometry_3d_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@
#include <fuse_core/uuid.hpp>
#include <fuse_models/common/sensor_proc.hpp>
#include <fuse_models/odometry_3d_publisher.hpp>
#include <fuse_models/unicycle_3d_predict.hpp>
#include <fuse_models/omnidirectional_3d_predict.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <pluginlib/class_list_macros.hpp>
Expand Down
Loading

0 comments on commit 72ff6a9

Please sign in to comment.