diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 64a792b8..412cb3a5 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,17 @@ Changelog for package plotjuggler_ros ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.1 (2020-12-18) +------------------ +* Added TF messages to the parser (issue `#366 `_) +* Update README.md +* Update README.md +* Merge pull request `#1 `_ from uhobeike/development + Made it possible to install +* Made it possible to install +* fix includes +* Contributors: Davide Faconti, davide, uhobeike + 1.0.0 (2020-11-23) ------------------ diff --git a/README.md b/README.md index cd2a85d9..f09eb169 100644 --- a/README.md +++ b/README.md @@ -29,7 +29,7 @@ Create a catkin workspace and clone the repositories: mkdir -p ~/ws_plotjuggler/src cd ~/ws_plotjuggler/src git clone https://github.com/PlotJuggler/plotjuggler_msgs.git - git clone https://github.com/PlotJuggler/PlotJuggler.git + git clone https://github.com/facontidavide/PlotJuggler.git git clone https://github.com/PlotJuggler/plotjuggler-ros-plugins.git Now, it is time to compile: diff --git a/package.xml b/package.xml index 10add671..9c6a48fa 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ plotjuggler_ros - 1.0.0 + 1.0.1 PlotJuggler plugin for ROS Davide Faconti diff --git a/plugins/ros1_parsers/diagnostic_msg.h b/plugins/ros1_parsers/diagnostic_msg.h index 6d2aa561..47e026aa 100644 --- a/plugins/ros1_parsers/diagnostic_msg.h +++ b/plugins/ros1_parsers/diagnostic_msg.h @@ -2,6 +2,7 @@ #include #include +#include "fmt/format.h" #include "ros1_parser.h" class DiagnosticMsgParser : public BuiltinMessageParser @@ -31,7 +32,8 @@ class DiagnosticMsgParser : public BuiltinMessageParser +#include +#include "ros2_parser.h" +#include "fmt/format.h" + +class DiagnosticMsgParser : public BuiltinMessageParser +{ +public: + DiagnosticMsgParser(const std::string& topic_name, PJ::PlotDataMapRef& plot_data) + : BuiltinMessageParser(topic_name, plot_data) + { + } + + virtual void parseMessageImpl(const diagnostic_msgs::msg::DiagnosticArray& msg, double timestamp) override + { + double header_stamp = double(msg.header.stamp.sec) + double(msg.header.stamp.nanosec) * 1e-9; + timestamp = (_use_header_stamp && header_stamp > 0) ? header_stamp : timestamp; + + auto stamp_series = &getSeries("/header/seq"); + stamp_series->pushBack( {timestamp, header_stamp} ); + + std::string key; + + for (const auto& status : msg.status) + { + for (const auto& kv : status.values) + { + const char* start_ptr = kv.value.data(); + double val = 0; + + bool parsed = boost::spirit::qi::parse(start_ptr, start_ptr + kv.value.size(), + boost::spirit::qi::double_, val); + if (!parsed){ + continue; + } + + if (status.hardware_id.empty()) + { + key = fmt::format("{}/{}/{}", _topic_name, status.name, kv.key); + } + else + { + key = fmt::format("{}/{}/{}/{}", _topic_name, status.hardware_id, status.name, kv.key); + } + auto& series = getSeries(key); + series.pushBack({ timestamp, val }); + } + } + } + +}; + diff --git a/plugins/ros2_parsers/imu_msg.h b/plugins/ros2_parsers/imu_msg.h index 34834d62..ed60321e 100644 --- a/plugins/ros2_parsers/imu_msg.h +++ b/plugins/ros2_parsers/imu_msg.h @@ -16,16 +16,16 @@ class ImuMsgParser : public BuiltinMessageParser , _lin_acc_covariance(topic_name + "/linear_acceleration_covariance", plot_data) , _ang_vel_covariance(topic_name + "/angular_velocity_covariance", plot_data) { - _data.push_back(&getSeries(plot_data, topic_name + "/header/stamp/sec")); - _data.push_back(&getSeries(plot_data, topic_name + "/header/stamp/nanosec")); + _data.push_back(&getSeries(topic_name + "/header/stamp/sec")); + _data.push_back(&getSeries(topic_name + "/header/stamp/nanosec")); - _data.push_back(&getSeries(plot_data, topic_name + "/angular_velocity/x")); - _data.push_back(&getSeries(plot_data, topic_name + "/angular_velocity/y")); - _data.push_back(&getSeries(plot_data, topic_name + "/angular_velocity/z")); + _data.push_back(&getSeries(topic_name + "/angular_velocity/x")); + _data.push_back(&getSeries(topic_name + "/angular_velocity/y")); + _data.push_back(&getSeries(topic_name + "/angular_velocity/z")); - _data.push_back(&getSeries(plot_data, topic_name + "/linear_acceleration/x")); - _data.push_back(&getSeries(plot_data, topic_name + "/linear_acceleration/y")); - _data.push_back(&getSeries(plot_data, topic_name + "/linear_acceleration/z")); + _data.push_back(&getSeries(topic_name + "/linear_acceleration/x")); + _data.push_back(&getSeries(topic_name + "/linear_acceleration/y")); + _data.push_back(&getSeries(topic_name + "/linear_acceleration/z")); } void parseMessageImpl(const sensor_msgs::msg::Imu& msg, double timestamp) override diff --git a/plugins/ros2_parsers/jointstates_msg.h b/plugins/ros2_parsers/jointstates_msg.h index 62867120..28a1fcd2 100644 --- a/plugins/ros2_parsers/jointstates_msg.h +++ b/plugins/ros2_parsers/jointstates_msg.h @@ -9,8 +9,8 @@ class JointStateMsgParser : public BuiltinMessageParser(topic_name, plot_data) { - _data.push_back(&getSeries(plot_data, topic_name + "/header/stamp/sec")); - _data.push_back(&getSeries(plot_data, topic_name + "/header/stamp/nanosec")); + _data.push_back(&getSeries(topic_name + "/header/stamp/sec")); + _data.push_back(&getSeries(topic_name + "/header/stamp/nanosec")); } void parseMessageImpl(const sensor_msgs::msg::JointState& msg, double timestamp) override @@ -29,19 +29,19 @@ class JointStateMsgParser : public BuiltinMessageParser , _pose_parser(topic_name + "/pose", plot_data) , _twist_parser(topic_name + "/twist", plot_data) { - _data.push_back(&getSeries(plot_data, topic_name + "/header/stamp/sec")); - _data.push_back(&getSeries(plot_data, topic_name + "/header/stamp/nanosec")); + _data.push_back(&getSeries(topic_name + "/header/stamp/sec")); + _data.push_back(&getSeries(topic_name + "/header/stamp/nanosec")); } void parseMessageImpl(const nav_msgs::msg::Odometry& msg, double timestamp) override diff --git a/plugins/ros2_parsers/pose_msg.h b/plugins/ros2_parsers/pose_msg.h index 0c488b42..4a5ccf32 100644 --- a/plugins/ros2_parsers/pose_msg.h +++ b/plugins/ros2_parsers/pose_msg.h @@ -14,9 +14,9 @@ class PoseMsgParser : public BuiltinMessageParser : BuiltinMessageParser(topic_name, plot_data) , _quat_parser(topic_name + "/orientation", plot_data) { - _data.push_back(&getSeries(plot_data, topic_name + "/position/x")); - _data.push_back(&getSeries(plot_data, topic_name + "/position/y")); - _data.push_back(&getSeries(plot_data, topic_name + "/position/z")); + _data.push_back(&getSeries(topic_name + "/position/x")); + _data.push_back(&getSeries(topic_name + "/position/y")); + _data.push_back(&getSeries(topic_name + "/position/z")); } void parseMessageImpl(const geometry_msgs::msg::Pose& msg, double timestamp) override @@ -39,8 +39,8 @@ class PoseStampedMsgParser : public BuiltinMessageParser(topic_name, plot_data), _pose_parser(topic_name, plot_data) { - _data.push_back(&getSeries(plot_data, topic_name + "/header/stamp/sec")); - _data.push_back(&getSeries(plot_data, topic_name + "/header/stamp/nanosec")); + _data.push_back(&getSeries(topic_name + "/header/stamp/sec")); + _data.push_back(&getSeries(topic_name + "/header/stamp/nanosec")); } void parseMessageImpl(const geometry_msgs::msg::PoseStamped& msg, double timestamp) override diff --git a/plugins/ros2_parsers/quaternion_msg.h b/plugins/ros2_parsers/quaternion_msg.h index 3fef4fce..a37f6abb 100644 --- a/plugins/ros2_parsers/quaternion_msg.h +++ b/plugins/ros2_parsers/quaternion_msg.h @@ -9,14 +9,14 @@ class QuaternionMsgParser : public BuiltinMessageParser(topic_name, plot_data) { - _data.push_back(&getSeries(plot_data, topic_name + "/x")); - _data.push_back(&getSeries(plot_data, topic_name + "/y")); - _data.push_back(&getSeries(plot_data, topic_name + "/z")); - _data.push_back(&getSeries(plot_data, topic_name + "/w")); + _data.push_back(&getSeries(topic_name + "/x")); + _data.push_back(&getSeries(topic_name + "/y")); + _data.push_back(&getSeries(topic_name + "/z")); + _data.push_back(&getSeries(topic_name + "/w")); - _data.push_back(&getSeries(plot_data, topic_name + "/roll_deg")); - _data.push_back(&getSeries(plot_data, topic_name + "/pitch_deg")); - _data.push_back(&getSeries(plot_data, topic_name + "/yaw_deg")); + _data.push_back(&getSeries(topic_name + "/roll_deg")); + _data.push_back(&getSeries(topic_name + "/pitch_deg")); + _data.push_back(&getSeries(topic_name + "/yaw_deg")); } void parseMessageImpl(const geometry_msgs::msg::Quaternion& msg, double timestamp) override diff --git a/plugins/ros2_parsers/ros2_parser.cpp b/plugins/ros2_parsers/ros2_parser.cpp index 2e14e1c4..07cf2503 100644 --- a/plugins/ros2_parsers/ros2_parser.cpp +++ b/plugins/ros2_parsers/ros2_parser.cpp @@ -2,14 +2,25 @@ #include "jointstates_msg.h" #include "imu_msg.h" #include "odometry_msg.h" +#include "tf_msg.h" #include "plotjuggler_msgs.h" - +#include "diagnostic_msg.h" void RosMessageParser::setUseHeaderStamp(bool use) { _use_header_stamp = use; } +PJ::PlotData& RosMessageParser::getSeries(const std::string key) +{ + auto plot_pair = _plot_data.numeric.find(key); + if (plot_pair == _plot_data.numeric.end()) + { + plot_pair = _plot_data.addNumeric(key); + } + return plot_pair->second; +} + PJ::PlotData& RosMessageParser::getSeries(PJ::PlotDataMapRef& plot_data, const std::string key) { auto plot_pair = plot_data.numeric.find(key); @@ -44,7 +55,7 @@ bool IntrospectionParser::parseMessage(const rcutils_uint8_array_t* serialized_m const auto& key = it.first; double value = it.second; - auto& series = getSeries(_plot_data, key); + auto& series = getSeries(key); if (!std::isnan(value) && !std::isinf(value)) { @@ -104,6 +115,14 @@ void CompositeParser::registerMessageType(const std::string& topic_name, const s { parser.reset(new JointStateMsgParser(topic_name, _plot_data)); } + else if (type == "diagnostic_msgs/DiagnosticArray") + { + parser.reset(new DiagnosticMsgParser(topic_name, _plot_data)); + } + else if (type == "tf2_msgs/TFMessage") + { + parser.reset(new TfMsgParser(topic_name, _plot_data)); + } else if (type == "geometry_msgs/Quaternion") { parser.reset(new QuaternionMsgParser(topic_name, _plot_data)); diff --git a/plugins/ros2_parsers/ros2_parser.h b/plugins/ros2_parsers/ros2_parser.h index 4acddd4b..0c339c69 100644 --- a/plugins/ros2_parsers/ros2_parser.h +++ b/plugins/ros2_parsers/ros2_parser.h @@ -44,10 +44,17 @@ class RosMessageParser virtual bool parseMessage(const MessageRef* serialized_msg, double timestamp) = 0; + PJ::PlotData& getSeries(const std::string key); + static PJ::PlotData& getSeries(PJ::PlotDataMapRef& plot_data, const std::string key); virtual const rosidl_message_type_support_t* typeSupport() const = 0; + PJ::PlotDataMapRef& plotData() + { + return _plot_data; + } + protected: bool _use_header_stamp; const std::string _topic_name; diff --git a/plugins/ros2_parsers/tf_msg.h b/plugins/ros2_parsers/tf_msg.h new file mode 100644 index 00000000..e88f8197 --- /dev/null +++ b/plugins/ros2_parsers/tf_msg.h @@ -0,0 +1,63 @@ +#pragma once + +#include +#include "fmt/format.h" +#include "ros2_parser.h" + +class TfMsgParser : public BuiltinMessageParser +{ +public: + + TfMsgParser(const std::string& topic_name, PJ::PlotDataMapRef& plot_data) : + BuiltinMessageParser(topic_name, plot_data) + { + } + + void parseMessageImpl(const tf2_msgs::msg::TFMessage& msg, double timestamp) override + { + using namespace PJ; + + for (const auto& trans : msg.transforms) + { + double header_stamp = double(trans.header.stamp.sec) + double(trans.header.stamp.nanosec) * 1e-9; + timestamp = (_use_header_stamp && header_stamp > 0) ? header_stamp : timestamp; + + std::string prefix; + if (trans.header.frame_id.empty()) + { + prefix = fmt::format("{}/{}", _topic_name, trans.child_frame_id); + } + else + { + prefix = fmt::format("{}/{}/{}", _topic_name, trans.header.frame_id, trans.child_frame_id); + } + + PlotData* series = &getSeries( prefix + "/header/stamp"); + series->pushBack({ timestamp, header_stamp }); + + series = &getSeries( prefix + "/translation/x"); + series->pushBack({ timestamp, trans.transform.translation.x }); + + series = &getSeries( prefix + "/translation/y"); + series->pushBack({ timestamp, trans.transform.translation.y }); + + series = &getSeries( prefix + "/translation/z"); + series->pushBack({ timestamp, trans.transform.translation.z }); + + series = &getSeries( prefix + "/rotation/x"); + series->pushBack({ timestamp, trans.transform.rotation.x }); + + series = &getSeries( prefix + "/rotation/y"); + series->pushBack({ timestamp, trans.transform.rotation.y }); + + series = &getSeries( prefix + "/rotation/z"); + series->pushBack({ timestamp, trans.transform.rotation.z }); + + series = &getSeries( prefix + "/rotation/w"); + series->pushBack({ timestamp, trans.transform.rotation.w }); + } + } +private: + +}; + diff --git a/plugins/ros2_parsers/twist_msg.h b/plugins/ros2_parsers/twist_msg.h index e820a5ff..aec49cf2 100644 --- a/plugins/ros2_parsers/twist_msg.h +++ b/plugins/ros2_parsers/twist_msg.h @@ -12,13 +12,13 @@ class TwistMsgParser : public BuiltinMessageParser TwistMsgParser(const std::string& topic_name, PJ::PlotDataMapRef& plot_data) : BuiltinMessageParser(topic_name, plot_data) { - _data.push_back(&getSeries(plot_data, topic_name + "/linear/x")); - _data.push_back(&getSeries(plot_data, topic_name + "/linear/y")); - _data.push_back(&getSeries(plot_data, topic_name + "/linear/z")); + _data.push_back(&getSeries(topic_name + "/linear/x")); + _data.push_back(&getSeries(topic_name + "/linear/y")); + _data.push_back(&getSeries(topic_name + "/linear/z")); - _data.push_back(&getSeries(plot_data, topic_name + "/angular/x")); - _data.push_back(&getSeries(plot_data, topic_name + "/angular/y")); - _data.push_back(&getSeries(plot_data, topic_name + "/angular/z")); + _data.push_back(&getSeries(topic_name + "/angular/x")); + _data.push_back(&getSeries(topic_name + "/angular/y")); + _data.push_back(&getSeries(topic_name + "/angular/z")); } void parseMessageImpl(const geometry_msgs::msg::Twist& msg, double timestamp) override @@ -43,8 +43,8 @@ class TwistStampedMsgParser : public BuiltinMessageParser(topic_name, plot_data) , _twist_parser(topic_name, plot_data) { - _data.push_back(&getSeries(plot_data, topic_name + "/header/stamp/sec")); - _data.push_back(&getSeries(plot_data, topic_name + "/header/stamp/nanosec")); + _data.push_back(&getSeries(topic_name + "/header/stamp/sec")); + _data.push_back(&getSeries(topic_name + "/header/stamp/nanosec")); } void parseMessageImpl(const geometry_msgs::msg::TwistStamped& msg, double timestamp) override