Skip to content

Commit

Permalink
refactor: change nodes
Browse files Browse the repository at this point in the history
  • Loading branch information
maroqijalil committed May 26, 2023
1 parent c02e764 commit 284d741
Show file tree
Hide file tree
Showing 4 changed files with 22 additions and 22 deletions.
11 changes: 7 additions & 4 deletions include/kansei/fallen/node/fallen_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,28 +25,31 @@
#include <string>

#include "kansei/fallen/node/fallen_determinant.hpp"
#include "kansei_interfaces/msg/fallen.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/int8.hpp"

namespace kansei::fallen
{

class FallenNode
{
public:
using Int8 = std_msgs::msg::Int8;

static std::string get_node_prefix();
static std::string fallen_topic();

explicit FallenNode(
rclcpp::Node::SharedPtr node, std::shared_ptr<FallenDeterminant> fallen_determinant);

void update(const keisan::Euler<double> & rpy, const keisan::Vector<3> & acc);

private:
std::string get_node_prefix() const;

void publish_fallen();

std::shared_ptr<FallenDeterminant> fallen_determinant;

rclcpp::Publisher<kansei_interfaces::msg::Fallen>::SharedPtr fallen_publisher;
rclcpp::Publisher<Int8>::SharedPtr fallen_publisher;
};

} // namespace kansei::fallen
Expand Down
6 changes: 3 additions & 3 deletions include/kansei/measurement/node/measurement_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@

#include "kansei/measurement/node/measurement_unit.hpp"
#include "kansei_interfaces/msg/axis.hpp"
#include "kansei_interfaces/msg/reset_orientation.hpp"
#include "kansei_interfaces/msg/status.hpp"
#include "kansei_interfaces/msg/unit.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/float64.hpp"

namespace kansei::measurement
{
Expand All @@ -38,7 +38,7 @@ class MeasurementNode
{
public:
using Axis = kansei_interfaces::msg::Axis;
using ResetOrientation = kansei_interfaces::msg::ResetOrientation;
using Float64 = std_msgs::msg::Float64;
using Status = kansei_interfaces::msg::Status;
using Unit = kansei_interfaces::msg::Unit;

Expand All @@ -60,7 +60,7 @@ class MeasurementNode

std::shared_ptr<MeasurementUnit> measurement_unit;

rclcpp::Subscription<ResetOrientation>::SharedPtr reset_orientation_subscriber;
rclcpp::Subscription<Float64>::SharedPtr reset_orientation_subscriber;

rclcpp::Publisher<Unit>::SharedPtr unit_publisher;
rclcpp::Subscription<Unit>::SharedPtr unit_subscriber;
Expand Down
19 changes: 8 additions & 11 deletions src/kansei/fallen/node/fallen_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,8 @@
// SOFTWARE.

#include <kansei_interfaces/msg/fallen.hpp>
#include <rclcpp/rclcpp.hpp>

#include <memory>
#include <rclcpp/rclcpp.hpp>
#include <string>

#include "kansei/fallen/fallen.hpp"
Expand All @@ -32,12 +31,15 @@ using namespace keisan::literals; // NOLINT
namespace kansei::fallen
{

std::string FallenNode::get_node_prefix() { return "fallen"; }

std::string FallenNode::fallen_topic() { return get_node_prefix() + "/fallen"; }

FallenNode::FallenNode(
rclcpp::Node::SharedPtr node, std::shared_ptr<FallenDeterminant> fallen_determinant)
: fallen_determinant(fallen_determinant)
{
fallen_publisher = node->create_publisher<kansei_interfaces::msg::Fallen>(
get_node_prefix() + "/fallen", 10);
fallen_publisher = node->create_publisher<Int8>(fallen_topic(), 10);
}

void FallenNode::update(const keisan::Euler<double> & rpy, const keisan::Vector<3> & acc)
Expand All @@ -55,16 +57,11 @@ void FallenNode::update(const keisan::Euler<double> & rpy, const keisan::Vector<
}
}

std::string FallenNode::get_node_prefix() const
{
return "fallen";
}

void FallenNode::publish_fallen()
{
auto fallen_msg = kansei_interfaces::msg::Fallen();
auto fallen_msg = Int8();

fallen_msg.fallen_status = fallen_determinant->get_fallen_status();
fallen_msg.data = fallen_determinant->get_fallen_status();

fallen_publisher->publish(fallen_msg);
}
Expand Down
8 changes: 4 additions & 4 deletions src/kansei/measurement/node/measurement_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,12 +50,12 @@ MeasurementNode::MeasurementNode(
rclcpp::Node::SharedPtr node, std::shared_ptr<MeasurementUnit> measurement_unit)
: measurement_unit(measurement_unit)
{
reset_orientation_subscriber = node->create_subscription<ResetOrientation>(
reset_orientation_topic(), 10, [this](const ResetOrientation::SharedPtr message) {
if (message->orientation == 0.0) {
reset_orientation_subscriber = node->create_subscription<Float64>(
reset_orientation_topic(), 10, [this](const Float64::SharedPtr message) {
if (message->data == 0.0) {
this->measurement_unit->reset_orientation();
} else {
this->measurement_unit->set_orientation_to(keisan::make_degree(message->orientation));
this->measurement_unit->set_orientation_to(keisan::make_degree(message->data));
}
});

Expand Down

0 comments on commit 284d741

Please sign in to comment.