diff --git a/.github/workflows/ubuntu.yml b/.github/workflows/ubuntu.yml index 13b2fed..326d71c 100644 --- a/.github/workflows/ubuntu.yml +++ b/.github/workflows/ubuntu.yml @@ -19,7 +19,7 @@ jobs: strategy: fail-fast: false matrix: - distro: [noetic] + distro: [foxy, humble, rolling] container: image: ros:${{ matrix.distro }} env: diff --git a/CMakeLists.txt b/CMakeLists.txt index 3eeab69..33abc16 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,29 +1,24 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5.0) project(trajectory_preview) -add_compile_options(-std=c++11) - -find_package(catkin REQUIRED COMPONENTS rviz sensor_msgs trajectory_msgs) +add_compile_options(-std=c++17) find_package(Qt5 REQUIRED COMPONENTS Widgets) -catkin_package( - INCLUDE_DIRS - include - LIBRARIES - ${PROJECT_NAME}_widget - ${PROJECT_NAME}_panel - CATKIN_DEPENDS - rviz - sensor_msgs - trajectory_msgs) +set(ROS2_DEPS + rviz_common + sensor_msgs + trajectory_msgs + pluginlib) + +find_package(ament_cmake REQUIRED) +foreach(dep ${ROS2_DEPS}) + find_package(${dep} REQUIRED) +endforeach() # ###################################################################################################################### # Build ## # ###################################################################################################################### - -include_directories(include ${catkin_INCLUDE_DIRS} ${CMAKE_CURRENT_BINARY_DIR}) - qt5_wrap_ui(UI_MOC ui/trajectory_preview_widget.ui) qt5_wrap_cpp(WIDGET_MOC include/${PROJECT_NAME}/trajectory_preview_widget.h src/trajectory_preview_impl.h) @@ -31,27 +26,33 @@ qt5_wrap_cpp(WIDGET_MOC include/${PROJECT_NAME}/trajectory_preview_widget.h src/ qt5_wrap_cpp(PANEL_MOC include/${PROJECT_NAME}/trajectory_preview_panel.h) # Widget Library -add_library(${PROJECT_NAME}_widget src/trajectory_preview_widget.cpp ${UI_MOC} ${WIDGET_MOC}) -target_link_libraries(${PROJECT_NAME}_widget ${catkin_LIBRARIES} Qt5::Widgets) +add_library(${PROJECT_NAME}_widget SHARED src/trajectory_preview_widget.cpp ${UI_MOC} ${WIDGET_MOC}) +target_include_directories(${PROJECT_NAME}_widget PUBLIC "$" + "$") +target_include_directories(${PROJECT_NAME}_widget PRIVATE "$") +target_link_libraries(${PROJECT_NAME}_widget Qt5::Widgets) +ament_target_dependencies(${PROJECT_NAME}_widget ${ROS2_DEPS}) # Panel Library -add_library(${PROJECT_NAME}_panel src/trajectory_preview_panel.cpp ${PANEL_MOC}) -target_link_libraries( - ${PROJECT_NAME}_panel - ${catkin_LIBRARIES} - Qt5::Widgets - ${PROJECT_NAME}_widget) +add_library(${PROJECT_NAME}_panel SHARED src/trajectory_preview_panel.cpp ${PANEL_MOC}) +target_link_libraries(${PROJECT_NAME}_panel Qt5::Widgets ${PROJECT_NAME}_widget) # ###################################################################################################################### # Install ## # ###################################################################################################################### -install( - TARGETS ${PROJECT_NAME}_widget ${PROJECT_NAME}_panel - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) +# Install the headers +install(DIRECTORY include/${PROJECT_NAME} DESTINATION include) + +# Install the library(ies) +install(TARGETS ${PROJECT_NAME}_widget ${PROJECT_NAME}_panel EXPORT ${PROJECT_NAME}-targets DESTINATION lib) + +install(FILES plugin_description.xml DESTINATION share/${PROJECT_NAME}) + +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) + +pluginlib_export_plugin_description_file(rviz_common plugin_description.xml) -install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) -install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) -install(FILES plugin_description.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +ament_export_targets(${PROJECT_NAME}-targets HAS_LIBRARY_TARGET) +ament_export_dependencies(${ROS2_DEPS}) +ament_package() diff --git a/include/trajectory_preview/trajectory_preview_panel.h b/include/trajectory_preview/trajectory_preview_panel.h index 55a49d6..7b00011 100644 --- a/include/trajectory_preview/trajectory_preview_panel.h +++ b/include/trajectory_preview/trajectory_preview_panel.h @@ -18,17 +18,17 @@ #ifndef TRAJECTORY_PREVIEW_PANEL_H #define TRAJECTORY_PREVIEW_PANEL_H -#include +#include namespace trajectory_preview { class TrajectoryPreviewWidget; -class TrajectoryPreviewPanel : public rviz::Panel +class TrajectoryPreviewPanel : public rviz_common::Panel { Q_OBJECT public: - using rviz::Panel::Panel; + using rviz_common::Panel::Panel; void onInitialize() override; diff --git a/include/trajectory_preview/trajectory_preview_widget.h b/include/trajectory_preview/trajectory_preview_widget.h index 234117f..7ba53d9 100644 --- a/include/trajectory_preview/trajectory_preview_widget.h +++ b/include/trajectory_preview/trajectory_preview_widget.h @@ -19,7 +19,8 @@ #define TRAJECTORY_PREVIEW_TRAJECTORY_PREVIEW_WIDGET_H #include -#include +#include +#include namespace Ui { @@ -43,15 +44,8 @@ class TrajectoryPreviewWidget : public QWidget * @param input_traj_topic * @param output_state_topic */ - void initializeROS(const std::string& input_traj_topic, const std::string& output_state_topic); - - /** - * @brief Programmatically sets the displayed trajectory (rather than waiting - * for one to - * be published) - * @param trajectory - */ - void setTrajectory(const trajectory_msgs::JointTrajectory& trajectory); + void initializeROS(rclcpp::Node::SharedPtr node, const std::string& input_traj_topic, + const std::string& output_state_topic); protected Q_SLOTS: // User Interactions diff --git a/launch/robot_model_preview_pipeline.launch.xml b/launch/robot_model_preview_pipeline.launch.xml index b84475b..f72a298 100644 --- a/launch/robot_model_preview_pipeline.launch.xml +++ b/launch/robot_model_preview_pipeline.launch.xml @@ -1,18 +1,18 @@ - - + + + - - - [trajectory/joint_states] + + - - - + + + - + diff --git a/package.xml b/package.xml index 4bb67dd..9ac0c57 100644 --- a/package.xml +++ b/package.xml @@ -1,5 +1,6 @@ - + + trajectory_preview 0.0.0 The trajectory_preview package @@ -9,17 +10,18 @@ Apache 2.0 - catkin - rviz + ament_cmake + rviz_common sensor_msgs trajectory_msgs libqt5-widgets qtbase5-dev + pluginlib joint_state_publisher robot_state_publisher tf2_ros - + ament_cmake diff --git a/plugin_description.xml b/plugin_description.xml index bf7bcf0..9146f4a 100644 --- a/plugin_description.xml +++ b/plugin_description.xml @@ -1,7 +1,7 @@ - + + base_class_type="rviz_common::Panel"> A panel previewing robot trajectories diff --git a/src/robot_trajectory.h b/src/robot_trajectory.h index dc1a207..c9f2623 100644 --- a/src/robot_trajectory.h +++ b/src/robot_trajectory.h @@ -38,26 +38,27 @@ #define TRAJECTORY_PREVIEW_ROBOT_TRAJECTORY_H #include -#include -#include -#include +#include +#include +#include namespace trajectory_preview { class RobotTrajectory { public: - RobotTrajectory(const trajectory_msgs::JointTrajectory& trajectory) : trajectory_(trajectory) + RobotTrajectory(const trajectory_msgs::msg::JointTrajectory& trajectory) : trajectory_(trajectory) { - ros::Time last_time_stamp = trajectory_.header.stamp; - ros::Time this_time_stamp = last_time_stamp; + rclcpp::Time last_time_stamp = trajectory_.header.stamp; + rclcpp::Time this_time_stamp = last_time_stamp; for (std::size_t i = 0; i < trajectory_.points.size(); ++i) { - this_time_stamp = trajectory_.header.stamp + trajectory_.points[i].time_from_start; + this_time_stamp = + rclcpp::Time(trajectory_.header.stamp) + rclcpp::Duration(trajectory_.points[i].time_from_start); waypoints_.push_back(trajectory_.points[i]); - duration_from_previous_.push_back((this_time_stamp - last_time_stamp).toSec()); + duration_from_previous_.push_back((this_time_stamp - last_time_stamp).seconds()); last_time_stamp = this_time_stamp; } @@ -97,7 +98,7 @@ class RobotTrajectory } } - bool getStateAtDurationFromStart(const double request_duration, sensor_msgs::JointState& output_state) const + bool getStateAtDurationFromStart(const double request_duration, sensor_msgs::msg::JointState& output_state) const { // If there are no waypoints we can't do anything if (waypoints_.empty()) @@ -108,9 +109,6 @@ class RobotTrajectory double blend = 1.0; findWayPointIndicesForDurationAfterStart(request_duration, before, after, blend); - // ROS_INFO("Interpolating %.3f of the way between index %d and %d.", - // blend, before, after); - output_state = interpolate(waypoints_[before], waypoints_[after], blend); return true; @@ -135,10 +133,10 @@ class RobotTrajectory } private: - sensor_msgs::JointState interpolate(const trajectory_msgs::JointTrajectoryPoint& start, - const trajectory_msgs::JointTrajectoryPoint& end, const double t) const + sensor_msgs::msg::JointState interpolate(const trajectory_msgs::msg::JointTrajectoryPoint& start, + const trajectory_msgs::msg::JointTrajectoryPoint& end, const double t) const { - sensor_msgs::JointState out; + sensor_msgs::msg::JointState out; out.name = trajectory_.joint_names; out.position.resize(out.name.size()); @@ -150,9 +148,9 @@ class RobotTrajectory return out; } - trajectory_msgs::JointTrajectory trajectory_; + trajectory_msgs::msg::JointTrajectory trajectory_; - std::deque waypoints_; + std::deque waypoints_; std::deque duration_from_previous_; }; diff --git a/src/trajectory_preview_impl.h b/src/trajectory_preview_impl.h index 2cb47a9..00c996d 100644 --- a/src/trajectory_preview_impl.h +++ b/src/trajectory_preview_impl.h @@ -20,8 +20,11 @@ #include "robot_trajectory.h" #include -#include -#include +#include +#include +#include +#include +#include namespace { @@ -31,7 +34,7 @@ double trajectoryDuration(const trajectory_preview::RobotTrajectory& traj) return traj.getWayPointDurationFromStart(traj.getWayPointCount() - 1); } -const static double target_fps = 15.0; +const static double timer_period = 1.0 / 30.0; } // namespace @@ -45,24 +48,16 @@ class TrajectoryPreviewImpl : public QObject { } - void initialize(const std::string& input_traj_topic, const std::string& output_state_topic) + void initialize(rclcpp::Node::SharedPtr node, const std::string& input_traj_topic, + const std::string& output_state_topic) { - ros::NodeHandle nh; - - std::string urdf_xml_string, srdf_xml_string; - if (!nh.getParam("robot_description", urdf_xml_string) || - !nh.getParam("robot_description_semantic", srdf_xml_string)) - { - ROS_ERROR_STREAM("Failed to get URDF and/or SRDF"); - return; - } - - traj_sub_ = nh.subscribe(input_traj_topic, 1, &TrajectoryPreviewImpl::onNewTrajectory, this); - state_pub_ = nh.advertise(output_state_topic, 1, true); - timer_ = nh.createTimer(ros::Rate(target_fps), &TrajectoryPreviewImpl::onAnimateCallback, this, false, false); + node_ = node; + traj_sub_ = node_->create_subscription( + input_traj_topic, 1, std::bind(&TrajectoryPreviewImpl::onNewTrajectory, this, std::placeholders::_1)); + state_pub_ = node_->create_publisher(output_state_topic, rclcpp::SystemDefaultsQoS()); } - void onNewTrajectory(const trajectory_msgs::JointTrajectoryConstPtr& msg) + void onNewTrajectory(const trajectory_msgs::msg::JointTrajectory::SharedPtr msg) { stopDisplay(); @@ -80,19 +75,13 @@ class TrajectoryPreviewImpl : public QObject startDisplay(); } - void onAnimateCallback(const ros::TimerEvent& e) + void onAnimateCallback() { if (!display_traj_) return; - auto step = (e.current_real - e.last_real).toSec() * scale_; - if (e.last_real == ros::Time()) // Last time is zero if the timer gets restarted - { - step = 0; - } - // compute current time - current_time_ = current_time_ + step; + current_time_ = current_time_ + (timer_period * scale_); if (current_time_ < trajectory_duration_) { @@ -115,13 +104,14 @@ class TrajectoryPreviewImpl : public QObject if (!display_traj_) return; - sensor_msgs::JointState state_msg; + sensor_msgs::msg::JointState state_msg; // Compute the interpolated state display_traj_->getStateAtDurationFromStart(t, state_msg); // Display - state_pub_.publish(state_msg); + state_pub_->publish(state_msg); + emit update(t / trajectory_duration_); } void startDisplay() @@ -134,17 +124,26 @@ class TrajectoryPreviewImpl : public QObject // reset timer current_time_ = 0.0; } - timer_.start(); + + // Start the timer + timer_ = node_->create_wall_timer(std::chrono::milliseconds(long((timer_period / scale_) * 1000.0)), + std::bind(&TrajectoryPreviewImpl::onAnimateCallback, this)); } void stopDisplay() { - timer_.stop(); + if (timer_) + timer_->cancel(); } void setScale(double new_scale) { scale_ = new_scale; + if (timer_) + { + timer_->cancel(); + startDisplay(); + } } void setCurrentTime(int index, int num_indexes) @@ -168,9 +167,10 @@ class TrajectoryPreviewImpl : public QObject void update(double ratio); private: - ros::Subscriber traj_sub_; - ros::Publisher state_pub_; - ros::Timer timer_; + rclcpp::Node::SharedPtr node_; + rclcpp::Subscription::SharedPtr traj_sub_; + rclcpp::Publisher::SharedPtr state_pub_; + rclcpp::TimerBase::SharedPtr timer_; double trajectory_duration_; double current_time_; diff --git a/src/trajectory_preview_panel.cpp b/src/trajectory_preview_panel.cpp index e736f11..94ebbc3 100644 --- a/src/trajectory_preview_panel.cpp +++ b/src/trajectory_preview_panel.cpp @@ -17,14 +17,26 @@ */ #include "trajectory_preview/trajectory_preview_panel.h" #include "trajectory_preview/trajectory_preview_widget.h" + #include +#include +#include namespace trajectory_preview { void TrajectoryPreviewPanel::onInitialize() { + auto node = getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); + + // Declare and get the input trajectory + node->declare_parameter("trajectory_topic", "trajectory"); + auto input_topic = node->get_parameter("trajectory_topic").get_value(); + + node->declare_parameter("display_topic", "trajectory/joint_states"); + auto output_topic = node->get_parameter("display_topic").get_value(); + widget_ = new TrajectoryPreviewWidget(); - widget_->initializeROS("/trajectory", "/trajectory_preview"); + widget_->initializeROS(node, input_topic, output_topic); // Add the widget to the panel layout QVBoxLayout* layout = new QVBoxLayout(this); @@ -34,5 +46,5 @@ void TrajectoryPreviewPanel::onInitialize() } // namespace trajectory_preview -#include -PLUGINLIB_EXPORT_CLASS(trajectory_preview::TrajectoryPreviewPanel, rviz::Panel) +#include +PLUGINLIB_EXPORT_CLASS(trajectory_preview::TrajectoryPreviewPanel, rviz_common::Panel) diff --git a/src/trajectory_preview_widget.cpp b/src/trajectory_preview_widget.cpp index c558581..02e3c5c 100644 --- a/src/trajectory_preview_widget.cpp +++ b/src/trajectory_preview_widget.cpp @@ -29,15 +29,16 @@ TrajectoryPreviewWidget::TrajectoryPreviewWidget(QWidget* parent) : QWidget(pare num_ticks_ = ui_->timeSlider->maximum() - ui_->timeSlider->minimum(); // QT Events - connect(ui_->playButton, SIGNAL(clicked()), this, SLOT(onPlayPauseButton())); - connect(ui_->scaleSpinBox, SIGNAL(valueChanged(double)), this, SLOT(onScaleChanged(double))); - connect(ui_->timeSlider, SIGNAL(sliderMoved(int)), this, SLOT(onSliderChanged(int))); + connect(ui_->playButton, &QPushButton::clicked, this, &TrajectoryPreviewWidget::onPlayPauseButton); + connect(ui_->scaleSpinBox, QOverload::of(&QDoubleSpinBox::valueChanged), this, + &TrajectoryPreviewWidget::onScaleChanged); + connect(ui_->timeSlider, &QSlider::sliderMoved, this, &TrajectoryPreviewWidget::onSliderChanged); // Create ROS stuff impl_ = new TrajectoryPreviewImpl(); - connect(impl_, SIGNAL(newTrajectory(double)), this, SLOT(onNewTrajectory(double))); - connect(impl_, SIGNAL(update(double)), this, SLOT(onUpdate(double))); - connect(impl_, SIGNAL(trajectoryFinished()), this, SLOT(onTrajectoryFinished())); + connect(impl_, &TrajectoryPreviewImpl::newTrajectory, this, &TrajectoryPreviewWidget::onNewTrajectory); + connect(impl_, &TrajectoryPreviewImpl::update, this, &TrajectoryPreviewWidget::onUpdate); + connect(impl_, &TrajectoryPreviewImpl::trajectoryFinished, this, &TrajectoryPreviewWidget::onTrajectoryFinished); } TrajectoryPreviewWidget::~TrajectoryPreviewWidget() @@ -62,6 +63,7 @@ void TrajectoryPreviewWidget::onPlayPauseButton() void TrajectoryPreviewWidget::onScaleChanged(double new_scale) { impl_->setScale(new_scale); + ui_->playButton->setChecked(true); } void TrajectoryPreviewWidget::onSliderChanged(int new_position) @@ -74,7 +76,7 @@ void TrajectoryPreviewWidget::onNewTrajectory(double total_duration) ui_->timeSlider->setValue(ui_->timeSlider->minimum()); ui_->playButton->setChecked(true); ui_->playButton->setText(tr("Pause")); - ui_->totalLabel->setText(QString::number(total_duration, 'g', 4)); + ui_->totalLabel->setText(QString::number(total_duration, 'f', 2)); } void TrajectoryPreviewWidget::onTrajectoryFinished() @@ -87,17 +89,13 @@ void TrajectoryPreviewWidget::onUpdate(double ratio) { int tick = static_cast(ratio * num_ticks_ + 0.5); ui_->timeSlider->setValue(tick); - ui_->currentLabel->setText(QString::number(ratio * impl_->currentTrajectoryDuration(), 'g', 4)); -} - -void TrajectoryPreviewWidget::initializeROS(const std::string& input_traj_topic, const std::string& output_state_topic) -{ - impl_->initialize(input_traj_topic, output_state_topic); + ui_->currentLabel->setText(QString::number(ratio * impl_->currentTrajectoryDuration(), 'f', 2)); } -void TrajectoryPreviewWidget::setTrajectory(const trajectory_msgs::JointTrajectory& trajectory) +void TrajectoryPreviewWidget::initializeROS(rclcpp::Node::SharedPtr node, const std::string& input_traj_topic, + const std::string& output_state_topic) { - impl_->onNewTrajectory(boost::make_shared(trajectory)); + impl_->initialize(node, input_traj_topic, output_state_topic); } } // namespace trajectory_preview diff --git a/ui/trajectory_preview_widget.ui b/ui/trajectory_preview_widget.ui index 2602251..b193313 100644 --- a/ui/trajectory_preview_widget.ui +++ b/ui/trajectory_preview_widget.ui @@ -82,6 +82,12 @@ x + + 0.010000000000000 + + + 100.000000000000000 + 0.100000000000000