Go to the documentation of this file.
21 #include <sensor_msgs/JointState.h>
25 #include <canopen_chain_node/GetObject.h>
53 canopen_chain_node::GetObject srv;
54 srv.request.node = joint_name;
56 srv.request.cached =
false;
58 ROS_INFO_STREAM(
"Call \"get firmware\" service for \"" << joint_name <<
"\"");
64 if (!srv.response.success)
71 return srv.response.value;
92 std::vector<std::string> node_names;
93 for (
auto& rpci : rpc)
95 auto node_name = rpci.first.c_str();
96 node_names.push_back(node_name);
static const std::string JOINT_STATE_TOPIC
bool getParam(const std::string &key, bool &b) const
FirmwareCont getFirmwareVersions()
std::string getFirmwareVersionOfJoint(const std::string &joint_name)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
std::map< std::string, std::string > FirmwareCont
static constexpr std::size_t FIRMWARE_STRING_LENGTH
static const std::string CANOPEN_GETOBJECT_SERVICE_NAME
#define ROS_INFO_STREAM(args)
static std::vector< std::string > getNodeNames(const ros::NodeHandle &nh)
static const std::string GET_FIRMWARE_VERSION_OBJECT
static const std::string CANOPEN_NODES_PARAMETER_NAME
Exception thrown by the SystemInfo class in case of an error.
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::ServiceClient canopen_srv_get_client_
static void waitForService(const std::string service_name, const double retry_timeout=DEFAULT_RETRY_TIMEOUT, const double msg_output_period=DEFAULT_MSG_OUTPUT_PERIOD)
SystemInfo(ros::NodeHandle &nh)
const std::vector< std::string > joint_names_
prbt_support
Author(s):
autogenerated on Sat Nov 25 2023 03:51:49