Template Class NodeCanopenBasicMaster

Inheritance Relationships

Base Type

  • public ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >

Class Documentation

template<class NODETYPE>
class NodeCanopenBasicMaster : public ros2_canopen::node_interfaces::NodeCanopenMaster<NODETYPE>

Public Functions

inline NodeCanopenBasicMaster(NODETYPE *node)
inline virtual ~NodeCanopenBasicMaster()
virtual void activate(bool called_from_base) override
virtual void deactivate(bool called_from_base) override
virtual void init(bool called_from_base) override
void on_sdo_read(const std::shared_ptr<canopen_interfaces::srv::COReadID::Request> request, std::shared_ptr<canopen_interfaces::srv::COReadID::Response> response)

Read Service Data Object.

This Service is only available when the node is in active lifecycle state. It will return with success false in any other lifecycle state and log an RCLCPP_ERROR.

Parameters:
  • request

  • response

void on_sdo_write(const std::shared_ptr<canopen_interfaces::srv::COWriteID::Request> request, std::shared_ptr<canopen_interfaces::srv::COWriteID::Response> response)

Write Service Data Object.

This service is only available when the node is in active lifecycle state. It will return with success false in any other lifecycle state and log an RCLCPP_ERROR.

Parameters:
  • request

  • response

Protected Attributes

std::shared_ptr<LelyMasterBridge> master_bridge_
rclcpp::Service<canopen_interfaces::srv::COReadID>::SharedPtr sdo_read_service
rclcpp::Service<canopen_interfaces::srv::COWriteID>::SharedPtr sdo_write_service