mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
merged task_panel + task_solution_display into motion_planning_tasks folder
This commit is contained in:
parent
82758abc65
commit
022e29caa5
@ -65,8 +65,7 @@ install(TARGETS ${PROJECT_NAME}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
|
||||
install(DIRECTORY include/ DESTINATION include)
|
||||
install(FILES
|
||||
task_panel_rviz_plugin_description.xml
|
||||
task_solution_rviz_plugin_description.xml
|
||||
motion_planning_tasks_rviz_plugin_description.xml
|
||||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
||||
|
||||
add_subdirectory(src/stages)
|
||||
|
||||
16
motion_planning_tasks_rviz_plugin_description.xml
Normal file
16
motion_planning_tasks_rviz_plugin_description.xml
Normal file
@ -0,0 +1,16 @@
|
||||
<library path="libmotion_planning_tasks_rviz_plugin">
|
||||
<class name="moveit_task_constructor/Motion Planning Tasks"
|
||||
type="moveit_rviz_plugin::TaskPanel"
|
||||
base_class_type="rviz::Panel">
|
||||
<description>
|
||||
A panel widget to monitor and edit motion planning tasks
|
||||
</description>
|
||||
</class>
|
||||
<class name="moveit_task_constructor/Motion Planning Tasks"
|
||||
type="moveit_rviz_plugin::TaskDisplay"
|
||||
base_class_type="rviz::Display">
|
||||
<description>
|
||||
Monitor motion planning tasks and animate their solution trajectories
|
||||
</description>
|
||||
</class>
|
||||
</library>
|
||||
@ -22,7 +22,6 @@
|
||||
<test_depend>rosunit</test_depend>
|
||||
|
||||
<export>
|
||||
<rviz plugin="${prefix}/task_panel_rviz_plugin_description.xml"/>
|
||||
<rviz plugin="${prefix}/task_solution_rviz_plugin_description.xml"/>
|
||||
<rviz plugin="${prefix}/motion_planning_tasks_rviz_plugin_description.xml"/>
|
||||
</export>
|
||||
</package>
|
||||
|
||||
@ -11,7 +11,7 @@ if (CATKIN_ENABLE_TESTING)
|
||||
target_link_libraries(${PROJECT_NAME}-test-container ${PROJECT_NAME} gtest_main ${catkin_LIBRARIES})
|
||||
|
||||
catkin_add_gtest(${PROJECT_NAME}-test-task_model test_task_model.cpp)
|
||||
target_link_libraries(${PROJECT_NAME}-test-task_model moveit_task_panel_rviz_plugin gtest_main)
|
||||
target_link_libraries(${PROJECT_NAME}-test-task_model motion_planning_tasks_rviz_plugin gtest_main)
|
||||
endif()
|
||||
|
||||
add_executable(test_plan_current_state test_plan_current_state.cpp)
|
||||
|
||||
@ -1,9 +0,0 @@
|
||||
<library path="lib/libmoveit_task_panel_rviz_plugin">
|
||||
<class name="moveit_task_constructor/Motion Planning Tasks"
|
||||
type="moveit_rviz_plugin::TaskPanel"
|
||||
base_class_type="rviz::Panel">
|
||||
<description>
|
||||
A panel widget to monitor and edit planning tasks
|
||||
</description>
|
||||
</class>
|
||||
</library>
|
||||
@ -1,9 +0,0 @@
|
||||
<library path="libmoveit_task_solution_rviz_plugin">
|
||||
<class name="moveit_task_constructor/Task Solution Display"
|
||||
type="moveit_rviz_plugin::TaskSolutionDisplay"
|
||||
base_class_type="rviz::Display">
|
||||
<description>
|
||||
Animate task solution trajectories
|
||||
</description>
|
||||
</class>
|
||||
</library>
|
||||
@ -21,5 +21,4 @@ set(CMAKE_AUTOMOC ON)
|
||||
add_definitions(-DQT_NO_KEYWORDS)
|
||||
|
||||
add_subdirectory(visualization_tools)
|
||||
add_subdirectory(task_solution_display)
|
||||
add_subdirectory(task_panel)
|
||||
add_subdirectory(motion_planning_tasks)
|
||||
|
||||
26
visualization/motion_planning_tasks/CMakeLists.txt
Normal file
26
visualization/motion_planning_tasks/CMakeLists.txt
Normal file
@ -0,0 +1,26 @@
|
||||
set(MOVEIT_LIB_NAME motion_planning_tasks_rviz_plugin)
|
||||
|
||||
qt_wrap_ui(UIC_FILES task_panel.ui)
|
||||
|
||||
add_library(${MOVEIT_LIB_NAME}
|
||||
mainloop_processing.cpp
|
||||
stage_wrapper.cpp
|
||||
task_model.cpp
|
||||
task_panel.cpp
|
||||
task_display.cpp
|
||||
plugin_init.cpp
|
||||
${UIC_FILES}
|
||||
)
|
||||
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
|
||||
target_link_libraries(${MOVEIT_LIB_NAME}
|
||||
moveit_task_visualization_tools
|
||||
${catkin_LIBRARIES} ${QT_LIBRARIES}
|
||||
)
|
||||
target_include_directories(${MOVEIT_LIB_NAME}
|
||||
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}>
|
||||
PRIVATE $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>
|
||||
)
|
||||
|
||||
install(TARGETS ${MOVEIT_LIB_NAME}
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
|
||||
8
visualization/motion_planning_tasks/plugin_init.cpp
Normal file
8
visualization/motion_planning_tasks/plugin_init.cpp
Normal file
@ -0,0 +1,8 @@
|
||||
/* Author: Robert Haschke */
|
||||
|
||||
#include <pluginlib/class_list_macros.h>
|
||||
#include "task_display.h"
|
||||
#include "task_panel.h"
|
||||
|
||||
PLUGINLIB_EXPORT_CLASS(moveit_rviz_plugin::TaskDisplay, rviz::Display)
|
||||
PLUGINLIB_EXPORT_CLASS(moveit_rviz_plugin::TaskPanel, rviz::Panel)
|
||||
@ -36,7 +36,7 @@
|
||||
Desc: Wraps a task_solution_visualization playback class for Rviz into a stand alone display
|
||||
*/
|
||||
|
||||
#include "task_solution_display.h"
|
||||
#include "task_display.h"
|
||||
|
||||
#include <moveit_task_constructor/visualization_tools/task_solution_visualization.h>
|
||||
#include <moveit/rdf_loader/rdf_loader.h>
|
||||
@ -46,7 +46,7 @@
|
||||
|
||||
namespace moveit_rviz_plugin
|
||||
{
|
||||
TaskSolutionDisplay::TaskSolutionDisplay() : Display(), load_robot_model_(false)
|
||||
TaskDisplay::TaskDisplay() : Display(), load_robot_model_(false)
|
||||
{
|
||||
// The robot description property is only needed when using the trajectory playback standalone (not within motion
|
||||
// planning plugin)
|
||||
@ -57,18 +57,18 @@ TaskSolutionDisplay::TaskSolutionDisplay() : Display(), load_robot_model_(false)
|
||||
trajectory_visual_.reset(new TaskSolutionVisualization(this, this));
|
||||
}
|
||||
|
||||
TaskSolutionDisplay::~TaskSolutionDisplay()
|
||||
TaskDisplay::~TaskDisplay()
|
||||
{
|
||||
}
|
||||
|
||||
void TaskSolutionDisplay::onInitialize()
|
||||
void TaskDisplay::onInitialize()
|
||||
{
|
||||
Display::onInitialize();
|
||||
|
||||
trajectory_visual_->onInitialize(scene_node_, context_, update_nh_);
|
||||
}
|
||||
|
||||
void TaskSolutionDisplay::loadRobotModel()
|
||||
void TaskDisplay::loadRobotModel()
|
||||
{
|
||||
load_robot_model_ = false;
|
||||
rdf_loader_.reset(new rdf_loader::RDFLoader(robot_description_property_->getStdString()));
|
||||
@ -90,26 +90,26 @@ void TaskSolutionDisplay::loadRobotModel()
|
||||
trajectory_visual_->onEnable();
|
||||
}
|
||||
|
||||
void TaskSolutionDisplay::reset()
|
||||
void TaskDisplay::reset()
|
||||
{
|
||||
Display::reset();
|
||||
loadRobotModel();
|
||||
trajectory_visual_->reset();
|
||||
}
|
||||
|
||||
void TaskSolutionDisplay::onEnable()
|
||||
void TaskDisplay::onEnable()
|
||||
{
|
||||
Display::onEnable();
|
||||
load_robot_model_ = true; // allow loading of robot model in update()
|
||||
}
|
||||
|
||||
void TaskSolutionDisplay::onDisable()
|
||||
void TaskDisplay::onDisable()
|
||||
{
|
||||
Display::onDisable();
|
||||
trajectory_visual_->onDisable();
|
||||
}
|
||||
|
||||
void TaskSolutionDisplay::update(float wall_dt, float ros_dt)
|
||||
void TaskDisplay::update(float wall_dt, float ros_dt)
|
||||
{
|
||||
Display::update(wall_dt, ros_dt);
|
||||
|
||||
@ -119,13 +119,13 @@ void TaskSolutionDisplay::update(float wall_dt, float ros_dt)
|
||||
trajectory_visual_->update(wall_dt, ros_dt);
|
||||
}
|
||||
|
||||
void TaskSolutionDisplay::setName(const QString& name)
|
||||
void TaskDisplay::setName(const QString& name)
|
||||
{
|
||||
BoolProperty::setName(name);
|
||||
trajectory_visual_->setName(name);
|
||||
}
|
||||
|
||||
void TaskSolutionDisplay::changedRobotDescription()
|
||||
void TaskDisplay::changedRobotDescription()
|
||||
{
|
||||
if (isEnabled())
|
||||
reset();
|
||||
@ -58,14 +58,14 @@ namespace moveit_rviz_plugin
|
||||
{
|
||||
|
||||
MOVEIT_CLASS_FORWARD(TaskSolutionVisualization)
|
||||
class TaskSolutionDisplay : public rviz::Display
|
||||
class TaskDisplay : public rviz::Display
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
TaskSolutionDisplay();
|
||||
TaskDisplay();
|
||||
|
||||
virtual ~TaskSolutionDisplay();
|
||||
virtual ~TaskDisplay();
|
||||
|
||||
void loadRobotModel();
|
||||
|
||||
@ -107,9 +107,3 @@ void TaskPanel::load(const rviz::Config& config)
|
||||
}
|
||||
|
||||
#include "moc_task_panel.cpp"
|
||||
|
||||
// Tell pluginlib about this class. Every class which should be
|
||||
// loadable by pluginlib::ClassLoader must have these two lines
|
||||
// compiled in its .cpp file, outside of any namespace scope.
|
||||
#include <pluginlib/class_list_macros.h>
|
||||
PLUGINLIB_EXPORT_CLASS(moveit_rviz_plugin::TaskPanel, rviz::Panel)
|
||||
@ -1,20 +0,0 @@
|
||||
set(MOVEIT_LIB_NAME moveit_task_panel_rviz_plugin)
|
||||
|
||||
qt_wrap_ui(UIC_FILES task_panel.ui)
|
||||
|
||||
add_library(${MOVEIT_LIB_NAME}
|
||||
mainloop_processing.cpp
|
||||
stage_wrapper.cpp
|
||||
task_model.cpp
|
||||
task_panel.cpp
|
||||
${UIC_FILES}
|
||||
)
|
||||
target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${QT_LIBRARIES})
|
||||
target_include_directories(${MOVEIT_LIB_NAME}
|
||||
PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}
|
||||
PRIVATE ${CMAKE_CURRENT_BINARY_DIR}
|
||||
)
|
||||
|
||||
install(TARGETS ${MOVEIT_LIB_NAME}
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
|
||||
@ -1,21 +0,0 @@
|
||||
set(MOVEIT_LIB_NAME moveit_task_solution_rviz_plugin)
|
||||
|
||||
# Trajectory Display
|
||||
add_library(${MOVEIT_LIB_NAME}_core
|
||||
task_solution_display.cpp
|
||||
)
|
||||
set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
|
||||
target_link_libraries(${MOVEIT_LIB_NAME}_core
|
||||
moveit_task_visualization_tools
|
||||
${catkin_LIBRARIES} ${OGRE_LIBRARIES} ${QT_LIBRARIES} ${Boost_LIBRARIES}
|
||||
)
|
||||
target_include_directories(${MOVEIT_LIB_NAME}_core PUBLIC include)
|
||||
|
||||
# Plugin Initializer
|
||||
add_library(${MOVEIT_LIB_NAME} plugin_init.cpp)
|
||||
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
|
||||
target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core ${catkin_LIBRARIES} ${Boost_LIBRARIES})
|
||||
|
||||
install(TARGETS ${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
|
||||
@ -1,40 +0,0 @@
|
||||
/*********************************************************************
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, Willow Garage, 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 Willow Garage 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.
|
||||
*********************************************************************/
|
||||
|
||||
/* Author: Dave Coleman */
|
||||
|
||||
#include <class_loader/class_loader.h>
|
||||
#include <task_solution_display.h>
|
||||
|
||||
CLASS_LOADER_REGISTER_CLASS(moveit_rviz_plugin::TaskSolutionDisplay, rviz::Display)
|
||||
Loading…
Reference in New Issue
Block a user