Skip to content

Commit

Permalink
navigation: moves node to base class
Browse files Browse the repository at this point in the history
  • Loading branch information
GuillaumeLaine committed Nov 23, 2023
1 parent 2495962 commit 7f40f10
Show file tree
Hide file tree
Showing 5 changed files with 6 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,6 @@ class GlobalNavigationInterface : public NavigationInterfaceBase<GlobalPositionE
*/
bool _isValueNotNAN(const GlobalPositionEstimate & estimate) const override;

rclcpp::Node & _node;
rclcpp::Publisher<AuxGlobalPosition>::SharedPtr _aux_global_position_pub;

// uint8_t _altitude_frame;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,6 @@ class LocalNavigationInterface : public NavigationInterfaceBase<LocalPositionEst
*/
bool _isValueNotNAN(const LocalPositionEstimate & estimate) const override;

rclcpp::Node & _node;
rclcpp::Publisher<AuxLocalPosition>::SharedPtr _aux_local_position_pub;

uint8_t _pose_frame;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,8 @@ template<typename EstimateType>
class NavigationInterfaceBase
{
public:
explicit NavigationInterfaceBase() = default;
explicit NavigationInterfaceBase(Context & context)
: _node(context.node()) {}
virtual ~NavigationInterfaceBase() = default;

/**
Expand All @@ -29,6 +30,8 @@ class NavigationInterfaceBase
virtual bool _isVarianceValid(const EstimateType & estimate) const = 0;
virtual bool _isFrameValid(const EstimateType & estimate) const = 0;
virtual bool _isValueNotNAN(const EstimateType & estimate) const = 0;

rclcpp::Node & _node;
};

} // namespace px4_ros2
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ namespace px4_ros2
{

GlobalNavigationInterface::GlobalNavigationInterface(Context & context)
: _node(context.node())
: NavigationInterfaceBase(context)
{
_aux_global_position_pub =
context.node().create_publisher<AuxGlobalPosition>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ namespace px4_ros2
LocalNavigationInterface::LocalNavigationInterface(
Context & context, const uint8_t pose_frame,
const uint8_t velocity_frame)
: _node(context.node())
: NavigationInterfaceBase(context)
{
// Check that selected pose and velocity reference frames are valid
auto it_pose_frame = std::find(
Expand Down

0 comments on commit 7f40f10

Please sign in to comment.