3#include <google/protobuf/util/json_util.h>
4#include <google/protobuf/util/type_resolver_util.h>
6#include "clproto/encoders.hpp"
7#include "clproto/decoders.hpp"
9#include <state_representation/State.hpp>
10#include <state_representation/AnalogIOState.hpp>
11#include <state_representation/DigitalIOState.hpp>
12#include <state_representation/parameters/Parameter.hpp>
13#include <state_representation/space/SpatialState.hpp>
14#include <state_representation/space/cartesian/CartesianState.hpp>
15#include <state_representation/space/cartesian/CartesianPose.hpp>
16#include <state_representation/space/cartesian/CartesianTwist.hpp>
17#include <state_representation/space/cartesian/CartesianAcceleration.hpp>
18#include <state_representation/space/cartesian/CartesianWrench.hpp>
19#include <state_representation/space/Jacobian.hpp>
20#include <state_representation/space/joint/JointState.hpp>
21#include <state_representation/space/joint/JointPositions.hpp>
22#include <state_representation/space/joint/JointVelocities.hpp>
23#include <state_representation/space/joint/JointAccelerations.hpp>
24#include <state_representation/space/joint/JointTorques.hpp>
26#include "state_representation/state_message.pb.h"
32DecodingException::DecodingException(
const std::string&
msg) : std::runtime_error(
msg) {}
34JsonParsingException::JsonParsingException(
const std::string& msg) : std::runtime_error(msg) {}
41 if (proto::StateMessage message; message.ParseFromString(msg)) {
42 return static_cast<MessageType>(message.message_type_case());
60 return MessageType::UNKNOWN_MESSAGE;
64 if (proto::StateMessage message; message.ParseFromString(msg) && message.has_parameter()) {
65 return static_cast<ParameterMessageType>(message.parameter().parameter_value().value_type_case());
67 return ParameterMessageType::UNKNOWN_PARAMETER;
72void pack_fields(
const std::vector<std::string>& fields,
char* data) {
73 std::size_t index = 0;
83 for (std::size_t field = 0; field < nfields; ++field) {
84 sizes[field] =
static_cast<field_length_t>(fields.at(field).size());
90 for (std::size_t field = 0; field < nfields; ++field) {
91 memcpy(&data[index], fields.at(field).c_str(), sizes[field]);
92 index += sizes[field];
97 std::size_t index = 0;
100 char field_buffer[CLPROTO_PACKING_MAX_FIELD_LENGTH];
101 std::vector<std::string> fields;
112 for (std::size_t field = 0; field < nfields; ++field) {
113 memcpy(field_buffer, &data[index], sizes[field]);
114 fields.emplace_back(std::string(field_buffer, sizes[field]));
115 index += sizes[field];
125 auto resolver = std::unique_ptr<google::protobuf::util::TypeResolver>{
126 google::protobuf::util::NewTypeResolverForDescriptorPool(
127 "", google::protobuf::DescriptorPool::generated_pool())
130 auto status = google::protobuf::util::BinaryToJsonString(
131 resolver.get(),
"/state_representation.proto.StateMessage", msg, std::addressof(json));
133 if (!status.ok() || json.size() <= 2) {
134 throw JsonParsingException(
"Could not parse the binary data into a JSON formatted state message");
142 auto resolver = std::unique_ptr<google::protobuf::util::TypeResolver>{
143 google::protobuf::util::NewTypeResolverForDescriptorPool(
144 "", google::protobuf::DescriptorPool::generated_pool())
147 auto status = google::protobuf::util::JsonToBinaryString(
148 resolver.get(),
"/state_representation.proto.StateMessage", json, std::addressof(msg));
161std::string encode<State>(
const State& obj);
163State decode(
const std::string& msg);
165bool decode(
const std::string& msg,
State& obj);
167std::string encode<State>(
const State& obj) {
168 proto::StateMessage message;
169 *message.mutable_state() = encoder(obj);
170 return message.SerializeAsString();
176 throw DecodingException(
"Could not decode the message into a State");
183 proto::StateMessage message;
184 if (!(message.ParseFromString(msg)
185 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kState)) {
189 auto state = message.state();
190 obj =
State(state.name());
209 proto::StateMessage message;
210 *message.mutable_analog_io_state() =
encoder(obj);
211 return message.SerializeAsString();
217 throw DecodingException(
"Could not decode the message into a AnalogIOState");
224 proto::StateMessage message;
225 if (!(message.ParseFromString(msg)
226 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kAnalogIoState)) {
230 auto state = message.analog_io_state();
232 if (!state.state().empty()) {
252 proto::StateMessage message;
253 *message.mutable_digital_io_state() =
encoder(obj);
254 return message.SerializeAsString();
260 throw DecodingException(
"Could not decode the message into a DigitalIOState");
267 proto::StateMessage message;
268 if (!(message.ParseFromString(msg)
269 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kDigitalIoState)) {
273 auto state = message.digital_io_state();
275 if (!state.state().empty()) {
288std::string encode<SpatialState>(
const SpatialState& obj);
294std::string encode<SpatialState>(
const SpatialState& obj) {
295 proto::StateMessage message;
296 *message.mutable_spatial_state() =
encoder(obj);
297 return message.SerializeAsString();
303 throw DecodingException(
"Could not decode the message into a SpatialState");
310 proto::StateMessage message;
311 if (!(message.ParseFromString(msg)
312 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kSpatialState)) {
316 auto spatial_state = message.spatial_state();
317 obj =
SpatialState(spatial_state.state().name(), spatial_state.reference_frame());
336 proto::StateMessage message;
337 *message.mutable_cartesian_state() =
encoder(obj);
338 return message.SerializeAsString();
344 throw DecodingException(
"Could not decode the message into a CartesianState");
351 proto::StateMessage message;
352 if (!(message.ParseFromString(msg)
353 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kCartesianState)) {
357 auto state = message.cartesian_state();
358 obj =
CartesianState(state.spatial_state().state().name(), state.spatial_state().reference_frame());
359 if (!state.spatial_state().state().empty()) {
386 proto::StateMessage message;
388 *message.mutable_cartesian_pose()->mutable_spatial_state() = cartesian_state.spatial_state();
389 if (!cartesian_state.spatial_state().state().empty()) {
390 *message.mutable_cartesian_pose()->mutable_position() = cartesian_state.position();
391 *message.mutable_cartesian_pose()->mutable_orientation() = cartesian_state.orientation();
393 return message.SerializeAsString();
399 throw DecodingException(
"Could not decode the message into a CartesianPose");
406 proto::StateMessage message;
407 if (!(message.ParseFromString(msg)
408 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kCartesianPose)) {
411 auto pose = message.cartesian_pose();
412 obj =
CartesianPose(pose.spatial_state().state().name(), pose.spatial_state().reference_frame());
413 if (!pose.spatial_state().state().empty()) {
434 proto::StateMessage message;
436 *message.mutable_cartesian_twist()->mutable_spatial_state() = cartesian_state.spatial_state();
437 if (!cartesian_state.spatial_state().state().empty()) {
438 *message.mutable_cartesian_twist()->mutable_linear_velocity() = cartesian_state.linear_velocity();
439 *message.mutable_cartesian_twist()->mutable_angular_velocity() = cartesian_state.angular_velocity();
441 return message.SerializeAsString();
447 throw DecodingException(
"Could not decode the message into a CartesianTwist");
454 proto::StateMessage message;
455 if (!(message.ParseFromString(msg)
456 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kCartesianTwist)) {
459 auto twist = message.cartesian_twist();
460 obj =
CartesianTwist(twist.spatial_state().state().name(), twist.spatial_state().reference_frame());
461 if (!twist.spatial_state().state().empty()) {
482 proto::StateMessage message;
484 *message.mutable_cartesian_acceleration()->mutable_spatial_state() = cartesian_state.spatial_state();
485 if (!cartesian_state.spatial_state().state().empty()) {
486 *message.mutable_cartesian_acceleration()->mutable_linear_acceleration() = cartesian_state.linear_acceleration();
487 *message.mutable_cartesian_acceleration()->mutable_angular_acceleration() = cartesian_state.angular_acceleration();
489 return message.SerializeAsString();
495 throw DecodingException(
"Could not decode the message into a CartesianAcceleration");
502 proto::StateMessage message;
503 if (!(message.ParseFromString(msg)
504 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kCartesianAcceleration)) {
507 auto acceleration = message.cartesian_acceleration();
509 acceleration.spatial_state().state().name(), acceleration.spatial_state().reference_frame());
510 if (!acceleration.spatial_state().state().empty()) {
531 proto::StateMessage message;
533 *message.mutable_cartesian_wrench()->mutable_spatial_state() = cartesian_state.spatial_state();
534 if (!cartesian_state.spatial_state().state().empty()) {
535 *message.mutable_cartesian_wrench()->mutable_force() = cartesian_state.force();
536 *message.mutable_cartesian_wrench()->mutable_torque() = cartesian_state.torque();
538 return message.SerializeAsString();
544 throw DecodingException(
"Could not decode the message into a CartesianWrench");
551 proto::StateMessage message;
552 if (!(message.ParseFromString(msg)
553 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kCartesianWrench)) {
556 auto wrench = message.cartesian_wrench();
557 obj =
CartesianWrench(wrench.spatial_state().state().name(), wrench.spatial_state().reference_frame());
558 if (!wrench.spatial_state().state().empty()) {
572std::string encode<Jacobian>(
const Jacobian& obj);
578std::string encode<Jacobian>(
const Jacobian& obj) {
579 proto::StateMessage message;
580 *message.mutable_jacobian() =
encoder(obj);
581 return message.SerializeAsString();
587 throw DecodingException(
"Could not decode the message into a Jacobian");
594 proto::StateMessage message;
595 if (!(message.ParseFromString(msg)
596 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kJacobian)) {
600 auto jacobian = message.jacobian();
602 jacobian.state().name(),
decoder(jacobian.joint_names()), jacobian.frame(), jacobian.reference_frame());
603 if (!jacobian.state().empty() && !jacobian.data().empty()) {
604 auto raw_data =
const_cast<double*
>(jacobian.data().data());
605 auto data = Eigen::Map<Eigen::MatrixXd>(raw_data, jacobian.rows(), jacobian.cols());
618std::string encode<JointState>(
const JointState& obj);
624std::string encode<JointState>(
const JointState& obj) {
625 proto::StateMessage message;
626 *message.mutable_joint_state() =
encoder(obj);
627 return message.SerializeAsString();
633 throw DecodingException(
"Could not decode the message into a JointState");
640 proto::StateMessage message;
641 if (!(message.ParseFromString(msg)
642 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kJointState)) {
646 auto state = message.joint_state();
648 if (!state.state().empty()) {
671 proto::StateMessage message;
673 *message.mutable_joint_positions()->mutable_state() = joint_state.state();
674 *message.mutable_joint_positions()->mutable_joint_names() = joint_state.joint_names();
675 if (!joint_state.state().empty()) {
676 *message.mutable_joint_positions()->mutable_positions() = joint_state.positions();
678 return message.SerializeAsString();
684 throw DecodingException(
"Could not decode the message into a JointPositions");
691 proto::StateMessage message;
692 if (!(message.ParseFromString(msg)
693 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kJointPositions)) {
697 auto positions = message.joint_positions();
699 if (!positions.state().empty()) {
719 proto::StateMessage message;
721 *message.mutable_joint_velocities()->mutable_state() = joint_state.state();
722 *message.mutable_joint_velocities()->mutable_joint_names() = joint_state.joint_names();
723 if (!joint_state.state().empty()) {
724 *message.mutable_joint_velocities()->mutable_velocities() = joint_state.velocities();
726 return message.SerializeAsString();
732 throw DecodingException(
"Could not decode the message into a JointVelocities");
739 proto::StateMessage message;
740 if (!(message.ParseFromString(msg)
741 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kJointVelocities)) {
745 auto velocities = message.joint_velocities();
747 if (!velocities.state().empty()) {
767 proto::StateMessage message;
769 *message.mutable_joint_accelerations()->mutable_state() = joint_state.state();
770 *message.mutable_joint_accelerations()->mutable_joint_names() = joint_state.joint_names();
771 if (!joint_state.state().empty()) {
772 *message.mutable_joint_accelerations()->mutable_accelerations() = joint_state.accelerations();
774 return message.SerializeAsString();
780 throw DecodingException(
"Could not decode the message into a JointAccelerations");
787 proto::StateMessage message;
788 if (!(message.ParseFromString(msg)
789 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kJointAccelerations)) {
793 auto accelerations = message.joint_accelerations();
795 if (!accelerations.state().empty()) {
808std::string encode<JointTorques>(
const JointTorques& obj);
814std::string encode<JointTorques>(
const JointTorques& obj) {
815 proto::StateMessage message;
817 *message.mutable_joint_torques()->mutable_state() = joint_state.state();
818 *message.mutable_joint_torques()->mutable_joint_names() = joint_state.joint_names();
819 if (!joint_state.state().empty()) {
820 *message.mutable_joint_torques()->mutable_torques() = joint_state.torques();
822 return message.SerializeAsString();
828 throw DecodingException(
"Could not decode the message into a JointTorques");
835 proto::StateMessage message;
836 if (!(message.ParseFromString(msg)
837 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kJointTorques)) {
841 auto torques = message.joint_torques();
843 if (!torques.state().empty()) {
856static std::string encode_parameter(
const Parameter<T>& obj);
858static Parameter<T> decode_parameter(
const std::string& msg);
860static bool decode_parameter(
const std::string& msg,
Parameter<T>& obj);
863static std::string encode_parameter(
const Parameter<T>& obj) {
864 proto::StateMessage message;
865 *message.mutable_parameter() = encoder<T>(obj);
866 return message.SerializeAsString();
869static Parameter<T> decode_parameter(
const std::string& msg) {
872 throw DecodingException(
"Could not decode the message into a Parameter");
877static bool decode_parameter(
const std::string& msg,
Parameter<T>& obj) {
879 proto::StateMessage message;
880 if (!(message.ParseFromString(msg)
881 && message.message_type_case() == proto::StateMessage::MessageTypeCase::kParameter)) {
884 obj = decoder<T>(message.parameter());
902 return encode_parameter(obj);
906 return decode_parameter<int>(msg);
910 return decode_parameter(msg, obj);
924 return encode_parameter(obj);
928 return decode_parameter<std::vector<int>>(msg);
932 return decode_parameter(msg, obj);
946 return encode_parameter(obj);
950 return decode_parameter<double>(msg);
954 return decode_parameter(msg, obj);
965bool decode(
const std::string& msg,
Parameter<std::vector<double>>& obj);
968 return encode_parameter(obj);
972 return decode_parameter<std::vector<double>>(msg);
975bool decode(
const std::string& msg,
Parameter<std::vector<double>>& obj) {
976 return decode_parameter(msg, obj);
990 return encode_parameter(obj);
994 return decode_parameter<bool>(msg);
998 return decode_parameter(msg, obj);
1009bool decode(
const std::string& msg,
Parameter<std::vector<bool>>& obj);
1012 return encode_parameter(obj);
1016 return decode_parameter<std::vector<bool>>(msg);
1019bool decode(
const std::string& msg,
Parameter<std::vector<bool>>& obj) {
1020 return decode_parameter(msg, obj);
1034 return encode_parameter(obj);
1038 return decode_parameter<std::string>(msg);
1042 return decode_parameter(msg, obj);
1053bool decode(
const std::string& msg,
Parameter<std::vector<std::string>>& obj);
1056 return encode_parameter(obj);
1060 return decode_parameter<std::vector<std::string>>(msg);
1063bool decode(
const std::string& msg,
Parameter<std::vector<std::string>>& obj) {
1064 return decode_parameter(msg, obj);
1078 return encode_parameter(obj);
1082 return decode_parameter<Eigen::VectorXd>(msg);
1086 return decode_parameter(msg, obj);
1100 return encode_parameter(obj);
1104 return decode_parameter<Eigen::MatrixXd>(msg);
1108 return decode_parameter(msg, obj);
1115std::shared_ptr<T> safe_dynamic_pointer_cast(
const std::shared_ptr<State>& state) {
1116 auto new_state = std::dynamic_pointer_cast<T>(state);
1117 if (new_state ==
nullptr) {
1118 throw std::invalid_argument(
"Dynamic pointer casting of state failed.");
1123template<> std::string encode<std::shared_ptr<State>>(
const std::shared_ptr<State>& obj);
1124template<> std::shared_ptr<State>
decode(
const std::string& msg);
1125template<>
bool decode(
const std::string& msg, std::shared_ptr<State>& obj);
1126template<> std::string encode<std::shared_ptr<State>>(
const std::shared_ptr<State>& obj) {
1127 std::string message;
1129 case StateType::STATE:
1130 message = encode<State>(*obj);
1132 case StateType::DIGITAL_IO_STATE:
1133 message = encode<DigitalIOState>(*safe_dynamic_pointer_cast<DigitalIOState>(obj));
1135 case StateType::ANALOG_IO_STATE:
1136 message = encode<AnalogIOState>(*safe_dynamic_pointer_cast<AnalogIOState>(obj));
1138 case StateType::SPATIAL_STATE:
1139 message = encode<SpatialState>(*safe_dynamic_pointer_cast<SpatialState>(obj));
1141 case StateType::CARTESIAN_STATE:
1142 message = encode<CartesianState>(*safe_dynamic_pointer_cast<CartesianState>(obj));
1144 case StateType::CARTESIAN_POSE:
1145 message = encode<CartesianPose>(*safe_dynamic_pointer_cast<CartesianPose>(obj));
1147 case StateType::CARTESIAN_TWIST:
1148 message = encode<CartesianTwist>(*safe_dynamic_pointer_cast<CartesianTwist>(obj));
1150 case StateType::CARTESIAN_ACCELERATION:
1151 message = encode<CartesianAcceleration>(*safe_dynamic_pointer_cast<CartesianAcceleration>(obj));
1153 case StateType::CARTESIAN_WRENCH:
1154 message = encode<CartesianWrench>(*safe_dynamic_pointer_cast<CartesianWrench>(obj));
1156 case StateType::JOINT_STATE:
1157 message = encode<JointState>(*safe_dynamic_pointer_cast<JointState>(obj));
1159 case StateType::JOINT_POSITIONS:
1160 message = encode<JointPositions>(*safe_dynamic_pointer_cast<JointPositions>(obj));
1162 case StateType::JOINT_VELOCITIES:
1163 message = encode<JointVelocities>(*safe_dynamic_pointer_cast<JointVelocities>(obj));
1165 case StateType::JOINT_ACCELERATIONS:
1166 message = encode<JointAccelerations>(*safe_dynamic_pointer_cast<JointAccelerations>(obj));
1168 case StateType::JOINT_TORQUES:
1169 message = encode<JointTorques>(*safe_dynamic_pointer_cast<JointTorques>(obj));
1171 case StateType::JACOBIAN:
1172 message = encode<Jacobian>(*safe_dynamic_pointer_cast<Jacobian>(obj));
1174 case StateType::PARAMETER: {
1175 auto param_ptr = safe_dynamic_pointer_cast<ParameterInterface>(obj);
1176 switch (param_ptr->get_parameter_type()) {
1177 case ParameterType::BOOL:
1178 message = encode<Parameter<bool>>(*safe_dynamic_pointer_cast<Parameter<bool>>(param_ptr));
1180 case ParameterType::BOOL_ARRAY:
1181 message = encode<Parameter<std::vector<bool>>>(*safe_dynamic_pointer_cast<Parameter<std::vector<bool>>>(param_ptr));
1183 case ParameterType::INT:
1184 message = encode<Parameter<int>>(*safe_dynamic_pointer_cast<Parameter<int>>(param_ptr));
1186 case ParameterType::INT_ARRAY:
1187 message = encode<Parameter<std::vector<int>>>(*safe_dynamic_pointer_cast<Parameter<std::vector<int>>>(param_ptr));
1189 case ParameterType::DOUBLE:
1190 message = encode<Parameter<double>>(*safe_dynamic_pointer_cast<Parameter<double>>(param_ptr));
1192 case ParameterType::DOUBLE_ARRAY:
1193 message = encode<Parameter<std::vector<double>>>(*safe_dynamic_pointer_cast<Parameter<std::vector<double>>>(param_ptr));
1195 case ParameterType::STRING:
1196 message = encode<Parameter<std::string>>(*safe_dynamic_pointer_cast<Parameter<std::string>>(param_ptr));
1198 case ParameterType::STRING_ARRAY:
1199 message = encode<Parameter<std::vector<std::string>>>(*safe_dynamic_pointer_cast<Parameter<std::vector<std::string>>>(param_ptr));
1201 case ParameterType::VECTOR:
1202 message = encode<Parameter<Eigen::VectorXd>>(*safe_dynamic_pointer_cast<Parameter<Eigen::VectorXd>>(param_ptr));
1204 case ParameterType::MATRIX:
1205 message = encode<Parameter<Eigen::MatrixXd>>(*safe_dynamic_pointer_cast<Parameter<Eigen::MatrixXd>>(param_ptr));
1208 throw std::invalid_argument(
"The ParameterType contained by parameter " + param_ptr->get_name() +
" is unsupported.");
1214 throw std::invalid_argument(
"The StateType contained by state " + obj->
get_name() +
" is unsupported.");
1219template<> std::shared_ptr<State>
decode(
const std::string& msg) {
1220 std::shared_ptr<State> obj;
1222 case MessageType::STATE_MESSAGE:
1223 obj = make_shared_state(
State());
1225 case MessageType::DIGITAL_IO_STATE_MESSAGE:
1228 case MessageType::ANALOG_IO_STATE_MESSAGE:
1231 case MessageType::SPATIAL_STATE_MESSAGE:
1234 case MessageType::CARTESIAN_STATE_MESSAGE:
1237 case MessageType::CARTESIAN_POSE_MESSAGE:
1240 case MessageType::CARTESIAN_TWIST_MESSAGE:
1243 case MessageType::CARTESIAN_ACCELERATION_MESSAGE:
1246 case MessageType::CARTESIAN_WRENCH_MESSAGE:
1249 case MessageType::JOINT_STATE_MESSAGE:
1252 case MessageType::JOINT_POSITIONS_MESSAGE:
1255 case MessageType::JOINT_VELOCITIES_MESSAGE:
1258 case MessageType::JOINT_ACCELERATIONS_MESSAGE:
1261 case MessageType::JOINT_TORQUES_MESSAGE:
1264 case MessageType::JACOBIAN_MESSAGE:
1265 obj = make_shared_state(
Jacobian());
1267 case MessageType::PARAMETER_MESSAGE: {
1269 case ParameterMessageType::BOOL:
1272 case ParameterMessageType::BOOL_ARRAY:
1273 obj = make_shared_state(
Parameter<std::vector<bool>>(
""));
1275 case ParameterMessageType::INT:
1278 case ParameterMessageType::INT_ARRAY:
1279 obj = make_shared_state(
Parameter<std::vector<int>>(
""));
1281 case ParameterMessageType::DOUBLE:
1284 case ParameterMessageType::DOUBLE_ARRAY:
1285 obj = make_shared_state(
Parameter<std::vector<double>>(
""));
1287 case ParameterMessageType::STRING:
1290 case ParameterMessageType::STRING_ARRAY:
1291 obj = make_shared_state(
Parameter<std::vector<std::string>>(
""));
1293 case ParameterMessageType::VECTOR:
1296 case ParameterMessageType::MATRIX:
1300 throw std::invalid_argument(
"The ParameterMessageType contained by this message is unsupported.");
1306 throw std::invalid_argument(
"The MessageType contained by this message is unsupported.");
1310 throw DecodingException(
"Could not decode the message into a std::shared_ptr<State>");
1314template<>
bool decode(
const std::string& msg, std::shared_ptr<State>& obj) {
1316 switch (obj->get_type()) {
1317 case StateType::STATE:
1318 obj = make_shared_state(decode<State>(msg));
1320 case StateType::DIGITAL_IO_STATE:
1321 obj = make_shared_state(decode<DigitalIOState>(msg));
1323 case StateType::ANALOG_IO_STATE:
1324 obj = make_shared_state(decode<AnalogIOState>(msg));
1326 case StateType::SPATIAL_STATE:
1327 obj = make_shared_state(decode<SpatialState>(msg));
1329 case StateType::CARTESIAN_STATE:
1330 obj = make_shared_state(decode<CartesianState>(msg));
1332 case StateType::CARTESIAN_POSE:
1333 obj = make_shared_state(decode<CartesianPose>(msg));
1335 case StateType::CARTESIAN_TWIST:
1336 obj = make_shared_state(decode<CartesianTwist>(msg));
1338 case StateType::CARTESIAN_ACCELERATION:
1339 obj = make_shared_state(decode<CartesianAcceleration>(msg));
1341 case StateType::CARTESIAN_WRENCH:
1342 obj = make_shared_state(decode<CartesianWrench>(msg));
1344 case StateType::JOINT_STATE:
1345 obj = make_shared_state(decode<JointState>(msg));
1347 case StateType::JOINT_POSITIONS:
1348 obj = make_shared_state(decode<JointPositions>(msg));
1350 case StateType::JOINT_VELOCITIES:
1351 obj = make_shared_state(decode<JointVelocities>(msg));
1353 case StateType::JOINT_ACCELERATIONS:
1354 obj = make_shared_state(decode<JointAccelerations>(msg));
1356 case StateType::JOINT_TORQUES:
1357 obj = make_shared_state(decode<JointTorques>(msg));
1359 case StateType::JACOBIAN:
1360 obj = make_shared_state(decode<Jacobian>(msg));
1362 case StateType::PARAMETER: {
1363 auto param_ptr = safe_dynamic_pointer_cast<ParameterInterface>(obj);
1364 switch (param_ptr->get_parameter_type()) {
1365 case ParameterType::BOOL:
1368 case ParameterType::BOOL_ARRAY:
1369 obj = make_shared_state(decode<
Parameter<std::vector<bool>>>(msg));
1371 case ParameterType::INT:
1374 case ParameterType::INT_ARRAY:
1375 obj = make_shared_state(decode<
Parameter<std::vector<int>>>(msg));
1377 case ParameterType::DOUBLE:
1380 case ParameterType::DOUBLE_ARRAY:
1381 obj = make_shared_state(decode<
Parameter<std::vector<double>>>(msg));
1383 case ParameterType::STRING:
1386 case ParameterType::STRING_ARRAY:
1387 obj = make_shared_state(decode<
Parameter<std::vector<std::string>>>(msg));
1389 case ParameterType::VECTOR:
1392 case ParameterType::MATRIX:
1396 throw std::invalid_argument(
"The ParameterType contained by parameter " + param_ptr->get_name() +
" is unsupported.");
1402 throw std::invalid_argument(
"The StateType contained by state " + obj->get_name() +
" is unsupported.");
A JsonParsingException is raised whenever a JSON conversion operation fails due to invalid encoding.
Class to define acceleration in Cartesian space as 3D linear and angular acceleration vectors.
Class to define Cartesian pose in Cartesian space as 3D position and quaternion based orientation.
Class to represent a state in Cartesian space.
void set_orientation(const Eigen::Quaterniond &orientation)
Setter of the orientation.
void set_angular_acceleration(const Eigen::Vector3d &angular_acceleration)
Setter of the angular velocity attribute.
void set_force(const Eigen::Vector3d &force)
Setter of the force attribute.
void set_linear_acceleration(const Eigen::Vector3d &linear_acceleration)
Setter of the linear acceleration attribute.
void set_position(const Eigen::Vector3d &position)
Setter of the position.
void set_torque(const Eigen::Vector3d &torque)
Setter of the torque attribute.
void set_linear_velocity(const Eigen::Vector3d &linear_velocity)
Setter of the linear velocity attribute.
void set_angular_velocity(const Eigen::Vector3d &angular_velocity)
Setter of the angular velocity attribute.
Class to define twist in Cartesian space as 3D linear and angular velocity vectors.
Class to define wrench in Cartesian space as 3D force and torque vectors.
void set_data(const Eigen::Vector< T, Eigen::Dynamic > &data)
Set the values of the IO state from a single Eigen vector.
Class to define a robot Jacobian matrix.
void set_data(const Eigen::MatrixXd &data) override
Setter of the data attribute.
Class to define accelerations of the joints.
Class to define positions of the joints.
Class to define a state in joint space.
void set_accelerations(const Eigen::VectorXd &accelerations)
Setter of the accelerations attribute.
void set_positions(const Eigen::VectorXd &positions)
Setter of the positions attribute.
void set_torques(const Eigen::VectorXd &torques)
Setter of the torques attribute.
void set_velocities(const Eigen::VectorXd &velocities)
Setter of the velocities attribute.
Class to define torques of the joints.
Class to define velocities of the joints.
Class to represent name-value pairs of different types.
Abstract class to represent a state.
const std::string & get_name() const
Getter of the name attribute.
const StateType & get_type() const
Getter of the type attribute.
Bindings to encode and decode state objects into serialised binary message.
ParameterMessageType check_parameter_message_type(const std::string &msg)
Check which control libraries parameter type a serialized binary string can be decoded as,...
uint32_t field_length_t
Size type used to indicate number of fields and field data length in pack_fields() and unpack_fields(...
std::string from_json(const std::string &json)
Convert a JSON formatted state message description into a serialized binary string representation (wi...
MessageType check_message_type(const std::string &msg)
Check which control libraries message type a serialized binary string can be decoded as,...
T decode(const std::string &msg)
Decode a serialized binary string from wire format into a control libraries object instance.
MessageType
The MessageType enumeration contains the possible message types in the clproto.
std::vector< FieldT > decoder(const google::protobuf::RepeatedField< FieldT > &message)
Decoding helper method for a RepeatedField message into vector data.
std::string to_json(const std::string &msg)
Convert a serialized binary string from wire format into a JSON formatted state message description.
ParameterMessageType
The ParameterMessageType enumeration contains the possible value types contained in a parameter messa...
void pack_fields(const std::vector< std::string > &fields, char *data)
Pack an ordered vector of encoded field messages into a single data array.
std::string encode(const T &obj)
Encode a control libraries object into a serialized binary string representation (wire format).
state_representation::proto::Parameter encoder(state_representation::proto::Parameter &message, const state_representation::Parameter< ParamT > ¶meter)
Encoding helper method for the Parameter type.
std::vector< std::string > unpack_fields(const char *data)
Unpack a data array into an ordered vector of encoded field messages.
bool is_valid(const std::string &msg)
Check if a serialized binary string can be decoded into a support control libraries message type.
Core state variables and objects.