Skip to content
This repository has been archived by the owner on Sep 23, 2024. It is now read-only.

Commit

Permalink
Subscribe to Cyphal estop message, relay it into ROS, inform user via…
Browse files Browse the repository at this point in the history
… BASH output.
  • Loading branch information
aentinger committed Jan 23, 2024
1 parent 13b72fa commit 45b9d27
Show file tree
Hide file tree
Showing 3 changed files with 57 additions and 10 deletions.
8 changes: 8 additions & 0 deletions include/t07_robot/Node.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,10 @@

#include <memory>

#include <rclcpp/qos.hpp>
#include <rclcpp/rclcpp.hpp>

#include <std_msgs/msg/bool.hpp>
#include <std_msgs/msg/float32.hpp>

#include <cyphal++/cyphal++.h>
Expand Down Expand Up @@ -86,6 +88,12 @@ class Node : public rclcpp::Node
rclcpp::TimerBase::SharedPtr _motor_right_ctrl_loop_timer;
void init_motor_right();
void motor_right_ctrl_loop();

rclcpp::QoS _estop_qos_profile;
rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr _estop_pub;
cyphal::Subscription _estop_cyphal_sub;
bool _is_estop_active;
void init_estop();
};

/**************************************************************************************
Expand Down
4 changes: 4 additions & 0 deletions launch/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,10 @@ def generate_launch_description():
{'motor_right_rpm_port_id': 1001},
{'wheel_left_diameter_mm': 130.0},
{'wheel_right_diameter_mm': 130.0},
{'estop_topic': '/estop/actual'},
{'estop_topic_deadline_ms': 100},
{'estop_topic_liveliness_lease_duration': 1000},
{'estop_port_id': 100},
]
)
])
55 changes: 45 additions & 10 deletions src/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,18 +36,12 @@ Node::Node()
cyphal::Node::DEFAULT_MTU_SIZE}
, _node_mtx{}
, _node_start{std::chrono::steady_clock::now()}
, _motor_left_qos_profile
{
rclcpp::KeepLast(1),
rmw_qos_profile_sensor_data
}
, _motor_left_qos_profile{rclcpp::KeepLast(1), rmw_qos_profile_sensor_data}
, _motor_left_target{0. * m/s}
, _motor_right_qos_profile
{
rclcpp::KeepLast(1),
rmw_qos_profile_sensor_data
}
, _motor_right_qos_profile{rclcpp::KeepLast(1), rmw_qos_profile_sensor_data}
, _motor_right_target{0. * m/s}
, _estop_qos_profile{rclcpp::KeepLast(1), rmw_qos_profile_default}
, _is_estop_active{false}
{
declare_parameter("can_iface", "can0");
declare_parameter("can_node_id", 100);
Expand Down Expand Up @@ -80,6 +74,7 @@ Node::Node()

init_motor_left();
init_motor_right();
init_estop();

RCLCPP_INFO(get_logger(), "%s init complete.", get_name());
}
Expand Down Expand Up @@ -291,6 +286,46 @@ void Node::motor_right_ctrl_loop()
}
}

void Node::init_estop()
{
/* Initialize the ROS publisher. */
declare_parameter("estop_topic", "/estop/actual");
declare_parameter("estop_topic_deadline_ms", 100);
declare_parameter("estop_topic_liveliness_lease_duration", 1000);

auto const estop_topic = get_parameter("estop_topic").as_string();
auto const estop_topic_deadline = std::chrono::milliseconds(get_parameter("estop_topic_deadline_ms").as_int());
auto const estop_topic_liveliness_lease_duration = std::chrono::milliseconds(get_parameter("estop_topic_liveliness_lease_duration").as_int());

_estop_qos_profile.deadline(estop_topic_deadline);
_estop_qos_profile.liveliness(RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC);
_estop_qos_profile.liveliness_lease_duration(estop_topic_liveliness_lease_duration);

_estop_pub = create_publisher<std_msgs::msg::Bool>(estop_topic, _estop_qos_profile);

/* Initialize the Cyphal subscriber. */
declare_parameter("estop_port_id", 100);

_estop_cyphal_sub = _node_hdl.create_subscription<uavcan::primitive::scalar::Bit_1_0>(
get_parameter("estop_port_id").as_int(),
[this](uavcan::primitive::scalar::Bit_1_0 const & msg)
{
_is_estop_active = (msg.value == false);

if (_is_estop_active)
RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 5*1000UL, "emergency stop is active.");

static bool prev_is_estop_active = false;
if (!_is_estop_active && prev_is_estop_active)
RCLCPP_INFO(get_logger(), "emergency stop was released.");
prev_is_estop_active = _is_estop_active;

std_msgs::msg::Bool estop_msg;
estop_msg.data = _is_estop_active;
_estop_pub->publish(estop_msg);
});
}

/**************************************************************************************
* NAMESPACE
**************************************************************************************/
Expand Down

0 comments on commit 45b9d27

Please sign in to comment.