Skip to content

Commit

Permalink
Renaming pose_2d
Browse files Browse the repository at this point in the history
  • Loading branch information
ayrton04 committed Aug 14, 2019
1 parent b7d3be8 commit 9421063
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 34 deletions.
2 changes: 1 addition & 1 deletion fuse_models/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -94,9 +94,9 @@ add_library(
${PROJECT_NAME}
src/acceleration_2d/model.cpp
src/imu_2d/model.cpp
src/pose_2d/model.cpp
src/odometry_2d/model.cpp
src/odometry_2d/publisher.cpp
src/pose_2d.cpp
src/twist_2d/model.cpp
src/unicycle_2d/state_kinematic_constraint.cpp
src/unicycle_2d/ignition.cpp
Expand Down
2 changes: 1 addition & 1 deletion fuse_models/fuse_plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
published by another node
</description>
</class>
<class type="fuse_models::pose_2d::Model" base_class_type="fuse_core::SensorModel">
<class type="fuse_models::Pose2D" base_class_type="fuse_core::SensorModel">
<description>
An adapter-type sensor that produces absolute or relative pose constraints from information published by
another node
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef FUSE_MODELS_PARAMETERS_POSE_2D_MODEL_PARAMS_H
#define FUSE_MODELS_PARAMETERS_POSE_2D_MODEL_PARAMS_H
#ifndef FUSE_MODELS_PARAMETERS_POSE_2D_PARAMS_H
#define FUSE_MODELS_PARAMETERS_POSE_2D_PARAMS_H

#include <fuse_models/parameters/parameter_base.h>

Expand All @@ -51,9 +51,9 @@ namespace parameters
{

/**
* @brief Defines the set of parameters required by the pose_2d::Model class
* @brief Defines the set of parameters required by the Pose2D class
*/
struct Pose2DModelParams : public ParameterBase
struct Pose2DParams : public ParameterBase
{
public:
/**
Expand Down Expand Up @@ -84,4 +84,4 @@ struct Pose2DModelParams : public ParameterBase

} // namespace fuse_models

#endif // FUSE_MODELS_PARAMETERS_POSE_2D_MODEL_PARAMS_H
#endif // FUSE_MODELS_PARAMETERS_POSE_2D_PARAMS_H
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,10 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef FUSE_MODELS_POSE_2D_MODEL_H
#define FUSE_MODELS_POSE_2D_MODEL_H
#ifndef FUSE_MODELS_POSE_2D_H
#define FUSE_MODELS_POSE_2D_H

#include <fuse_models/parameters/pose_2d_model_params.h>
#include <fuse_models/parameters/pose_2d_params.h>

#include <fuse_core/async_sensor_model.h>
#include <fuse_core/uuid.h>
Expand All @@ -47,9 +47,6 @@
namespace fuse_models
{

namespace pose_2d
{

/**
* @brief An adapter-type sensor that produces absolute or relative pose constraints from information published by
* another node.
Expand All @@ -70,21 +67,21 @@ namespace pose_2d
* Subscribes:
* - \p topic (geometry_msgs::PoseWithCovarianceStamped) Absolute pose information at a given timestamp
*/
class Model : public fuse_core::AsyncSensorModel
class Pose2D : public fuse_core::AsyncSensorModel
{
public:
SMART_PTR_DEFINITIONS(Model);
using ParameterType = parameters::Pose2DModelParams;
SMART_PTR_DEFINITIONS(Pose2D);
using ParameterType = parameters::Pose2DParams;

/**
* @brief Default constructor
*/
Model();
Pose2D();

/**
* @brief Destructor
*/
virtual ~Model() = default;
virtual ~Pose2D() = default;

/**
* @brief Callback for pose messages
Expand Down Expand Up @@ -125,8 +122,6 @@ class Model : public fuse_core::AsyncSensorModel
ros::Subscriber subscriber_;
};

} // namespace pose_2d

} // namespace fuse_models

#endif // FUSE_MODELS_POSE_2D_MODEL_H
#endif // FUSE_MODELS_POSE_2D_H
22 changes: 9 additions & 13 deletions fuse_models/src/pose_2d/model.cpp → fuse_models/src/pose_2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*/
#include <fuse_models/common/sensor_proc.h>
#include <fuse_models/pose_2d/model.h>
#include <fuse_models/pose_2d.h>

#include <fuse_core/transaction.h>
#include <fuse_core/uuid.h>
Expand All @@ -43,22 +43,19 @@


// Register this sensor model with ROS as a plugin.
PLUGINLIB_EXPORT_CLASS(fuse_models::pose_2d::Model, fuse_core::SensorModel)
PLUGINLIB_EXPORT_CLASS(fuse_models::Pose2D, fuse_core::SensorModel)

namespace fuse_models
{

namespace pose_2d
{

Model::Model() :
Pose2D::Pose2D() :
fuse_core::AsyncSensorModel(1),
device_id_(fuse_core::uuid::NIL),
tf_listener_(tf_buffer_)
{
}

void Model::onInit()
void Pose2D::onInit()
{
// Read settings from the parameter sever
device_id_ = fuse_variables::loadDeviceId(private_node_handle_);
Expand All @@ -73,21 +70,22 @@ void Model::onInit()
}
}

void Model::onStart()
void Pose2D::onStart()
{
if (!params_.position_indices.empty() ||
!params_.orientation_indices.empty())
{
subscriber_ = node_handle_.subscribe(ros::names::resolve(params_.topic), params_.queue_size, &Model::process, this);
subscriber_ =
node_handle_.subscribe(ros::names::resolve(params_.topic), params_.queue_size, &Pose2D::process, this);
}
}

void Model::onStop()
void Pose2D::onStop()
{
subscriber_.shutdown();
}

void Model::process(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
void Pose2D::process(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
{
// Create a transaction object
auto transaction = fuse_core::Transaction::make_shared();
Expand Down Expand Up @@ -124,6 +122,4 @@ void Model::process(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& ms
sendTransaction(transaction);
}

} // namespace pose_2d

} // namespace fuse_models

0 comments on commit 9421063

Please sign in to comment.