Skip to content

Commit

Permalink
Added TwistStamped and AccelStamped default plugins (#991)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Jul 18, 2023
1 parent d8fb5d5 commit 9599dd4
Show file tree
Hide file tree
Showing 22 changed files with 1,606 additions and 0 deletions.
36 changes: 36 additions & 0 deletions rviz_default_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ find_package(urdf REQUIRED)
find_package(visualization_msgs REQUIRED)

set(rviz_default_plugins_headers_to_moc
include/rviz_default_plugins/displays/accel/accel_display.hpp
include/rviz_default_plugins/displays/axes/axes_display.hpp
include/rviz_default_plugins/displays/camera/camera_display.hpp
include/rviz_default_plugins/displays/effort/effort_display.hpp
Expand Down Expand Up @@ -111,9 +112,11 @@ set(rviz_default_plugins_headers_to_moc
include/rviz_default_plugins/displays/range/range_display.hpp
include/rviz_default_plugins/displays/relative_humidity/relative_humidity_display.hpp
include/rviz_default_plugins/displays/robot_model/robot_model_display.hpp
include/rviz_default_plugins/displays/screw/screw_display.hpp
include/rviz_default_plugins/displays/temperature/temperature_display.hpp
include/rviz_default_plugins/displays/tf/frame_info.hpp
include/rviz_default_plugins/displays/tf/tf_display.hpp
include/rviz_default_plugins/displays/twist/twist_display.hpp
include/rviz_default_plugins/displays/wrench/wrench_display.hpp
include/rviz_default_plugins/robot/robot.hpp
include/rviz_default_plugins/robot/robot_joint.hpp
Expand All @@ -134,6 +137,7 @@ foreach(header "${rviz_default_plugins_headers_to_moc}")
endforeach()

set(rviz_default_plugins_source_files
src/rviz_default_plugins/displays/accel/accel_display.cpp
src/rviz_default_plugins/displays/axes/axes_display.cpp
src/rviz_default_plugins/displays/camera/camera_display.cpp
src/rviz_default_plugins/displays/effort/effort_display.cpp
Expand Down Expand Up @@ -193,11 +197,13 @@ set(rviz_default_plugins_source_files
src/rviz_default_plugins/displays/range/range_display.cpp
src/rviz_default_plugins/displays/relative_humidity/relative_humidity_display.cpp
src/rviz_default_plugins/displays/robot_model/robot_model_display.cpp
src/rviz_default_plugins/displays/screw/screw_display.cpp
src/rviz_default_plugins/displays/temperature/temperature_display.cpp
src/rviz_default_plugins/displays/tf/frame_info.cpp
src/rviz_default_plugins/displays/tf/frame_selection_handler.cpp
src/rviz_default_plugins/displays/tf/tf_display.cpp
src/rviz_default_plugins/displays/wrench/wrench_display.cpp
src/rviz_default_plugins/displays/twist/twist_display.cpp
src/rviz_default_plugins/robot/robot.cpp
src/rviz_default_plugins/robot/robot_joint.cpp
src/rviz_default_plugins/robot/robot_link.cpp
Expand Down Expand Up @@ -717,6 +723,21 @@ if(BUILD_TESTING)
)
endif()

ament_add_gtest(accel_display_visual_test
test/rviz_default_plugins/displays/accel/accel_display_visual_test.cpp
test/rviz_default_plugins/page_objects/accel_display_page_object.cpp
${SKIP_VISUAL_TESTS}
TIMEOUT 180)
if(TARGET accel_display_visual_test)
target_include_directories(accel_display_visual_test PRIVATE test)
target_link_libraries(accel_display_visual_test
rviz_visual_testing_framework::rviz_visual_testing_framework
${geometry_msgs_TARGETS}
${std_msgs_TARGETS}
rclcpp::rclcpp
)
endif()

ament_add_gtest(axes_display_visual_test
test/rviz_default_plugins/displays/axes/axes_display_visual_test.cpp
test/rviz_default_plugins/page_objects/axes_display_page_object.cpp
Expand Down Expand Up @@ -1120,6 +1141,21 @@ if(BUILD_TESTING)
)
endif()

ament_add_gtest(twist_display_visual_test
test/rviz_default_plugins/displays/twist/twist_display_visual_test.cpp
test/rviz_default_plugins/page_objects/twist_display_page_object.cpp
${SKIP_VISUAL_TESTS}
TIMEOUT 180)
if(TARGET twist_display_visual_test)
target_include_directories(twist_display_visual_test PRIVATE test)
target_link_libraries(twist_display_visual_test
rviz_visual_testing_framework::rviz_visual_testing_framework
${geometry_msgs_TARGETS}
${std_msgs_TARGETS}
rclcpp::rclcpp
)
endif()

ament_add_gtest(wrench_display_visual_test
test/rviz_default_plugins/displays/wrench/wrench_stamped_display_visual_test.cpp
test/rviz_default_plugins/page_objects/wrench_display_page_object.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
/*
* Copyright (c) 2023, Open Source Robotics Foundation, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/


#ifndef RVIZ_DEFAULT_PLUGINS__DISPLAYS__ACCEL__ACCEL_DISPLAY_HPP_
#define RVIZ_DEFAULT_PLUGINS__DISPLAYS__ACCEL__ACCEL_DISPLAY_HPP_

#include <memory>

#include "rviz_default_plugins/displays/screw/screw_display.hpp"

#include <geometry_msgs/msg/accel_stamped.hpp>

namespace rviz_default_plugins
{
namespace displays
{
class AccelStampedDisplay : public ScrewDisplay<geometry_msgs::msg::AccelStamped>
{
Q_OBJECT

// Function to handle an incoming ROS message.
void processMessage(geometry_msgs::msg::AccelStamped::ConstSharedPtr msg) override;
};

} // namespace displays
} // namespace rviz_default_plugins

#endif // RVIZ_DEFAULT_PLUGINS__DISPLAYS__ACCEL__ACCEL_DISPLAY_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,95 @@
/*
* Copyright (c) 2023, Open Source Robotics Foundation, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef RVIZ_DEFAULT_PLUGINS__DISPLAYS__SCREW__SCREW_DISPLAY_HPP_
#define RVIZ_DEFAULT_PLUGINS__DISPLAYS__SCREW__SCREW_DISPLAY_HPP_

#include <deque>
#include <memory>

#include <geometry_msgs/msg/vector3.hpp>
#include <rviz_common/message_filter_display.hpp>
#include <rviz_common/properties/bool_property.hpp>
#include <rviz_common/properties/color_property.hpp>
#include <rviz_common/properties/int_property.hpp>
#include <rviz_common/properties/float_property.hpp>
#include <rviz_rendering/objects/screw_visual.hpp>
#include <std_msgs/msg/header.hpp>


#include "rviz_default_plugins/visibility_control.hpp"

namespace rviz_default_plugins
{
namespace displays
{
template<class MessageType>
class RVIZ_DEFAULT_PLUGINS_PUBLIC ScrewDisplay
: public rviz_common::MessageFilterDisplay<MessageType>
{
public:
// Constructor. pluginlib::ClassLoader creates instances by calling
// the default constructor, so make sure you have one.
ScrewDisplay();
~ScrewDisplay() override = default;

protected:
// Overrides of public virtual functions from the Display class.
void onInitialize() override;
void reset() override;

// Helper function to properties for all visuals.
void updateProperties();
void updateHistoryLength();

void processMessagePrivate(
const std_msgs::msg::Header & header,
const geometry_msgs::msg::Vector3 & linear,
const geometry_msgs::msg::Vector3 & angular);

// Storage for the list of visuals par each joint intem
// Storage for the list of visuals. It is a circular buffer where
// data gets popped from the front (oldest) and pushed to the back (newest)
std::deque<std::shared_ptr<rviz_rendering::ScrewVisual>> visuals_;

// Property objects for user-editable properties.
rviz_common::properties::ColorProperty * linear_color_property_;
rviz_common::properties::ColorProperty * angular_color_property_;
rviz_common::properties::FloatProperty * alpha_property_;
rviz_common::properties::FloatProperty * linear_scale_property_;
rviz_common::properties::FloatProperty * angular_scale_property_;
rviz_common::properties::FloatProperty * width_property_;
rviz_common::properties::IntProperty * history_length_property_;
rviz_common::properties::BoolProperty * hide_small_values_property_;
};

} // namespace displays
} // namespace rviz_default_plugins

#endif // RVIZ_DEFAULT_PLUGINS__DISPLAYS__SCREW__SCREW_DISPLAY_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
/*
* Copyright (c) 2023, Open Source Robotics Foundation, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/


#ifndef RVIZ_DEFAULT_PLUGINS__DISPLAYS__TWIST__TWIST_DISPLAY_HPP_
#define RVIZ_DEFAULT_PLUGINS__DISPLAYS__TWIST__TWIST_DISPLAY_HPP_

#include <memory>

#include "rviz_default_plugins/displays/screw/screw_display.hpp"

#include <geometry_msgs/msg/twist_stamped.hpp>

namespace rviz_default_plugins
{
namespace displays
{
class TwistStampedDisplay : public ScrewDisplay<geometry_msgs::msg::TwistStamped>
{
Q_OBJECT

// Function to handle an incoming ROS message.
void processMessage(geometry_msgs::msg::TwistStamped::ConstSharedPtr msg) override;
};

} // namespace displays
} // namespace rviz_default_plugins

#endif // RVIZ_DEFAULT_PLUGINS__DISPLAYS__TWIST__TWIST_DISPLAY_HPP_
21 changes: 21 additions & 0 deletions rviz_default_plugins/plugins_description.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,16 @@
<library path="rviz_default_plugins">

<!-- Displays plugins -->
<class
name="rviz_default_plugins/AccelStamped"
type="rviz_default_plugins::displays::AccelStampedDisplay"
base_class_type="rviz_common::Display"
>
<description>
Displays from geometry_msgs/AccelStamped message
</description>
<message_type>geometry_msgs/msg/AccelStamped</message_type>
</class>

<class
name="rviz_default_plugins/Axes"
Expand Down Expand Up @@ -231,6 +241,17 @@
<message_type>tf2_msgs/msg/TFMessage</message_type>
</class>

<class
name="rviz_default_plugins/TwistStamped"
type="rviz_default_plugins::displays::TwistStampedDisplay"
base_class_type="rviz_common::Display"
>
<description>
Displays from geometry_msgs/TwistStamped message
</description>
<message_type>geometry_msgs/msg/TwistStamped</message_type>
</class>

<class
name="rviz_default_plugins/Marker"
type="rviz_default_plugins::displays::MarkerDisplay"
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
/*
* Copyright (c) 2023, Open Source Robotics Foundation, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <rviz_default_plugins/displays/accel/accel_display.hpp>

// Tell pluginlib about these classes. It is important to do this in
// global scope, outside our package's namespace.
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(
rviz_default_plugins::displays::AccelStampedDisplay,
rviz_common::Display)

namespace rviz_default_plugins
{
namespace displays
{
// Function to handle an incoming ROS message.
void AccelStampedDisplay::processMessage(geometry_msgs::msg::AccelStamped::ConstSharedPtr msg)
{
processMessagePrivate(msg->header, msg->accel.linear, msg->accel.angular);
}
} // namespace displays
} // namespace rviz_default_plugins
Loading

0 comments on commit 9599dd4

Please sign in to comment.