Template Class NodeCanopenProxyDriver

Inheritance Relationships

Base Type

  • public NodeCanopenBaseDriver< NODETYPE >

Class Documentation

template<class NODETYPE>
class NodeCanopenProxyDriver : public NodeCanopenBaseDriver<NODETYPE>

Public Functions

NodeCanopenProxyDriver(NODETYPE *node)
virtual void init(bool called_from_base) override
virtual bool reset_node_nmt_command()
virtual bool start_node_nmt_command()
virtual bool tpdo_transmit(COData &data)
virtual bool sdo_write(COData &data)
virtual bool sdo_read(COData &data)

Protected Functions

virtual void on_nmt(canopen::NmtState nmt_state) override
virtual void on_rpdo(COData data) override
virtual void on_tpdo(const canopen_interfaces::msg::COData::SharedPtr msg)
virtual void diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper &stat) override
void on_nmt_state_reset(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)
void on_nmt_state_start(const std_srvs::srv::Trigger::Request::SharedPtr request, std_srvs::srv::Trigger::Response::SharedPtr response)
void on_sdo_read(const canopen_interfaces::srv::CORead::Request::SharedPtr request, canopen_interfaces::srv::CORead::Response::SharedPtr response)
void on_sdo_write(const canopen_interfaces::srv::COWrite::Request::SharedPtr request, canopen_interfaces::srv::COWrite::Response::SharedPtr response)

Protected Attributes

rclcpp::Publisher<std_msgs::msg::String>::SharedPtr nmt_state_publisher
rclcpp::Publisher<canopen_interfaces::msg::COData>::SharedPtr rpdo_publisher
rclcpp::Subscription<canopen_interfaces::msg::COData>::SharedPtr tpdo_subscriber
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr nmt_state_reset_service
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr nmt_state_start_service
rclcpp::Service<canopen_interfaces::srv::CORead>::SharedPtr sdo_read_service
rclcpp::Service<canopen_interfaces::srv::COWrite>::SharedPtr sdo_write_service
std::mutex sdo_mtex