Skip to content

Commit

Permalink
[gnss_poser] fix namespace for component (autowarefoundation#295)
Browse files Browse the repository at this point in the history
Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>
  • Loading branch information
TakaHoribe authored Jan 27, 2021
1 parent d0c2e44 commit 2508e19
Show file tree
Hide file tree
Showing 5 changed files with 10 additions and 11 deletions.
2 changes: 1 addition & 1 deletion sensing/preprocessor/gnss/gnss_poser/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ ament_auto_add_library(gnss_poser_node SHARED
)

rclcpp_components_register_node(gnss_poser_node
PLUGIN "GNSSPoser"
PLUGIN "gnss_poser::GNSSPoser"
EXECUTABLE gnss_poser
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include "sensor_msgs/msg/nav_sat_fix.hpp"
#include "rclcpp/logging.hpp"

namespace GNSSPoser
namespace gnss_poser
{
enum class MGRSPrecision
{
Expand Down Expand Up @@ -131,6 +131,6 @@ GNSSStat NavSatFix2PLANE(
plane.z = EllipsoidHeight2OrthometricHeight(nav_sat_fix_msg, logger);
return plane;
}
} // namespace GNSSPoser
} // namespace gnss_poser

#endif // GNSS_POSER__CONVERT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@

#include "boost/circular_buffer.hpp"

namespace GNSSPoser
namespace gnss_poser
{
class GNSSPoser : public rclcpp::Node
{
Expand Down Expand Up @@ -89,6 +89,6 @@ class GNSSPoser : public rclcpp::Node
boost::circular_buffer<geometry_msgs::msg::Point> position_buffer_;
ublox_msgs::msg::NavPVT::ConstSharedPtr nav_pvt_msg_ptr_;
};
} // namespace GNSSPoser
} // namespace gnss_poser

#endif // GNSS_POSER__GNSS_POSER_CORE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#ifndef GNSS_POSER__GNSS_STAT_HPP_
#define GNSS_POSER__GNSS_STAT_HPP_

namespace GNSSPoser
namespace gnss_poser
{
enum class CoordinateSystem
{
Expand Down Expand Up @@ -48,6 +48,6 @@ struct GNSSStat
double longitude;
double altitude;
};
} // namespace GNSSPoser
} // namespace gnss_poser

#endif // GNSS_POSER__GNSS_STAT_HPP_
7 changes: 3 additions & 4 deletions sensing/preprocessor/gnss/gnss_poser/src/gnss_poser_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include "gnss_poser/gnss_poser_core.hpp"

namespace GNSSPoser
namespace gnss_poser
{
GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options)
: rclcpp::Node("gnss_poser", node_options),
Expand Down Expand Up @@ -344,8 +344,7 @@ void GNSSPoser::publishTF(

tf2_broadcaster_.sendTransform(transform_stamped);
}
} // namespace gnss_poser

#include "rclcpp_components/register_node_macro.hpp"

RCLCPP_COMPONENTS_REGISTER_NODE(GNSSPoser)
} // namespace GNSSPoser
RCLCPP_COMPONENTS_REGISTER_NODE(gnss_poser::GNSSPoser)

0 comments on commit 2508e19

Please sign in to comment.