system_info.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Pilz GmbH & Co. KG
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8 
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13 
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
18 
19 #include <XmlRpcValue.h>
20 #include <XmlRpcException.h>
21 #include <sensor_msgs/JointState.h>
22 
25 #include <canopen_chain_node/GetObject.h>
27 
28 namespace prbt_support
29 {
30 static const std::string CANOPEN_GETOBJECT_SERVICE_NAME{ "/prbt/driver/get_object" };
31 static const std::string CANOPEN_NODES_PARAMETER_NAME{ "/prbt/driver/nodes" };
32 static const std::string JOINT_STATE_TOPIC{ "/joint_states" };
33 
34 static const std::string GET_FIRMWARE_VERSION_OBJECT{ "100A" };
35 
36 // Currently the string is defined to be 41 characters long, but the last character can be omitted.
37 // This is currently under investigation. See https://github.com/PilzDE/pilz_robots/issues/299.
38 static constexpr std::size_t FIRMWARE_STRING_LENGTH{ 40 };
39 
40 SystemInfo::SystemInfo(ros::NodeHandle& nh) : joint_names_(getNodeNames(nh))
41 {
42  // Wait till CAN is up and running.
43  // Reason: If the first CAN service call happens before
44  // the CAN is fully initialized, the CAN will not start properly.
45  pilz_utils::waitForMessage<sensor_msgs::JointState>(JOINT_STATE_TOPIC);
46 
48  canopen_srv_get_client_ = nh.serviceClient<canopen_chain_node::GetObject>(CANOPEN_GETOBJECT_SERVICE_NAME);
49 }
50 
51 std::string SystemInfo::getFirmwareVersionOfJoint(const std::string& joint_name)
52 {
53  canopen_chain_node::GetObject srv;
54  srv.request.node = joint_name;
55  srv.request.object = GET_FIRMWARE_VERSION_OBJECT;
56  srv.request.cached = false;
57 
58  ROS_INFO_STREAM("Call \"get firmware\" service for \"" << joint_name << "\"");
59  if (!canopen_srv_get_client_.call(srv))
60  {
61  throw SystemInfoException("CANopen service to request firmware version failed");
62  }
63 
64  if (!srv.response.success)
65  {
66  throw SystemInfoException(srv.response.message);
67  }
68 
69  srv.response.value.resize(FIRMWARE_STRING_LENGTH);
70 
71  return srv.response.value;
72 }
73 
75 {
76  FirmwareCont versions;
77  for (const auto& joint : joint_names_)
78  {
79  versions[joint] = getFirmwareVersionOfJoint(joint);
80  }
81  return versions;
82 }
83 
84 std::vector<std::string> SystemInfo::getNodeNames(const ros::NodeHandle& nh)
85 {
88  {
89  throw SystemInfoException("Could not read node names");
90  }
91 
92  std::vector<std::string> node_names;
93  for (auto& rpci : rpc)
94  {
95  auto node_name = rpci.first.c_str();
96  node_names.push_back(node_name);
97  }
98  return node_names;
99 }
100 
101 } // namespace prbt_support
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
const std::vector< std::string > joint_names_
Definition: system_info.h:62
static const std::string JOINT_STATE_TOPIC
Definition: system_info.cpp:32
std::map< std::string, std::string > FirmwareCont
Definition: system_info.h:33
Exception thrown by the SystemInfo class in case of an error.
ros::ServiceClient canopen_srv_get_client_
Definition: system_info.h:63
bool call(MReq &req, MRes &res)
static std::vector< std::string > getNodeNames(const ros::NodeHandle &nh)
Definition: system_info.cpp:84
SystemInfo(ros::NodeHandle &nh)
Definition: system_info.cpp:40
static constexpr std::size_t FIRMWARE_STRING_LENGTH
Definition: system_info.cpp:38
FirmwareCont getFirmwareVersions()
Definition: system_info.cpp:74
static const std::string CANOPEN_GETOBJECT_SERVICE_NAME
Definition: system_info.cpp:30
bool getParam(const std::string &key, std::string &s) const
static void waitForService(const std::string service_name, const double retry_timeout=DEFAULT_RETRY_TIMEOUT, const double msg_output_period=DEFAULT_MSG_OUTPUT_PERIOD)
std::string getFirmwareVersionOfJoint(const std::string &joint_name)
Definition: system_info.cpp:51
#define ROS_INFO_STREAM(args)
static const std::string CANOPEN_NODES_PARAMETER_NAME
Definition: system_info.cpp:31
static const std::string GET_FIRMWARE_VERSION_OBJECT
Definition: system_info.cpp:34


prbt_support
Author(s):
autogenerated on Mon Feb 28 2022 23:14:45