Class TwistMux
Defined in File twist_mux.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class TwistMux : public rclcpp::Node
The TwistMux class implements a top-level twist multiplexer module that priorize different velocity command topic inputs according to locks.
Public Types
-
using velocity_topic_container = handle_container<VelocityTopicHandle>
-
using lock_topic_container = handle_container<LockTopicHandle>
Public Functions
-
TwistMux()
-
~TwistMux() = default
-
void init()
-
bool hasPriority(const VelocityTopicHandle &twist)
-
void updateDiagnostics()
Protected Types
-
typedef TwistMuxDiagnostics diagnostics_type
-
typedef TwistMuxDiagnosticsStatus status_type
Protected Functions
-
template<typename T>
void getTopicHandles(const std::string ¶m_name, handle_container<T> &topic_hs)
-
int getLockPriority()
Protected Attributes
-
rclcpp::TimerBase::SharedPtr diagnostics_timer_
-
std::shared_ptr<velocity_topic_container> velocity_hs_
velocity_hs_ Velocity topics’ handles. Note that if we use a vector, as a consequence of the re-allocation and the fact that we have a subscriber inside with a pointer to ‘this’, we must reserve the number of handles initially.
-
std::shared_ptr<lock_topic_container> lock_hs_
-
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr cmd_pub_
-
geometry_msgs::msg::Twist last_cmd_
-
std::shared_ptr<diagnostics_type> diagnostics_
-
std::shared_ptr<status_type> status_
Protected Static Attributes
-
static constexpr std::chrono::duration<int64_t> DIAGNOSTICS_PERIOD = 1s
-
using velocity_topic_container = handle_container<VelocityTopicHandle>