diff --git a/README.md b/README.md index 0619268..07f1b34 100644 --- a/README.md +++ b/README.md @@ -88,11 +88,11 @@ source install/setup.bash ### Install as a single CMake project -If you want to build this repository as a single CMake project, you can use the `CMakeLists.txt` provided in `xcub_moveit2_all_packages`: +If you want to build this repository as a single CMake project, you can use the `CMakeLists.txt` provided in `xcub_moveit_all_packages`: ~~~shell git clone https://github.com/icub-tech-iit/xcub-moveit2/ -cd xcub-moveit2/xcub_moveit2_all_packages +cd xcub-moveit2/xcub_moveit_all_packages cmake -Bbuild -S. -DCMAKE_INSTALL_PREFIX= cmake --build build cmake --install build @@ -123,15 +123,15 @@ However, if you want to work in simulation instead of on the real hardware, you This section aims to give a brief description of what each package contains. -### robot_controller +### xcub_ros2_controllers -This package contains `robot_controller` plugin that is used in [ros2_control](https://control.ros.org/master/index.html) framework. It includes: +This package contains `xcub_ros2_controllers` plugin that is used in [ros2_control](https://control.ros.org/master/index.html) framework. It includes: - a `position state interface` used to read the position of each joint; - a `velocity state interface` used to read the velocity of each joint; - a `position command interface` used to forward the desired position to the joints. -### robot_moveit +### xcub_moveit_robot This package contains some launch files, depending on the nodes you want to run. @@ -140,11 +140,16 @@ This package contains some launch files, depending on the nodes you want to run. - **`robot_controls.launch.py`**: this launch file allows to run the `controller manager` node for ros2_control and the nodes for the single controllers (one for each part). - **`circle_demo.launch.py`** and **`grasp_demo.launch.py`**: as the name suggests, they are two examples of commanding the robot in the cartesian space using `torso + right_arm` as planning group. - Before running the nodes, make sure that your environment variable `YARP_ROBOT_NAME` is properly set with the name of your robot. If not, set it for each shell according to the chosen model, for example: ```shell -export YARP_ROBOT_NAME="icub" +export YARP_ROBOT_NAME="iCubGenova11" +``` + +or, for simulated models: + +```shell +export YARP_ROBOT_NAME="iCubGazeboV2_5" ``` ### icub_moveit_config @@ -155,11 +160,11 @@ This package contains the configuration files to make iCub working with MoveIt2. It contains the same information described in the previous paragraph, but customized with ergoCub specs. -### test_controller +### xcub_moveit_test_controller In this folder, a test to sample the reaching space is available. It can be run as a ros2 node with the provided launch file called `test_controller.launch.py`. For this purpose, you can find more info in the [Use case](#use-case) paragraph above. -Moreover, a detailed report about the controller performance can be found [here](https://github.com/icub-tech-iit/xcub-moveit2/blob/master/test_controller/README.md#test-on-the-controller-performance) 📝. +Moreover, a detailed report about the controller performance can be found [here](https://github.com/icub-tech-iit/xcub-moveit2/blob/master/xcub_test_controller/README.md#test-on-the-controller-performance) 📝. ## Use case @@ -175,10 +180,10 @@ colcon build source install/setup.bash # Remember to check if your robot name variable is set. If not: -export YARP_ROBOT_NAME="icub" +export YARP_ROBOT_NAME="iCubGazeboV2_5" # Launch the start-up nodes -ros2 launch robot_moveit robot_sim.launch.py +ros2 launch xcub_moveit_robot robot_sim.launch.py ``` In this way, both rviz2 and gazebo windows are opened with the iCub model spawned in the two environments. At this point, open another shell, build and source the enviroment and then launch the ros2_control nodes: @@ -188,10 +193,10 @@ cd ~/ source /opt/ros/humble/setup.bash colcon build source install/setup.bash -export YARP_ROBOT_NAME="icub" +export YARP_ROBOT_NAME="iCubGazeboV2_5" # Launch the ros2_control nodes -ros2 launch robot_moveit robot_controls.launch.py +ros2 launch xcub_moveit_robot robot_controls.launch.py ``` To verify that everthing has been done successfully, you can run in a separate shell: @@ -208,16 +213,16 @@ cd ~/ source /opt/ros/humble/setup.bash colcon build source install/setup.bash -export YARP_ROBOT_NAME="icub" +export YARP_ROBOT_NAME="iCubGazeboV2_5" # For the grasping demo -ros2 launch robot_moveit grasp_demo.launch.py +ros2 launch xcub_moveit_robot grasp_demo.launch.py ``` If you want to see iCub performing a circle movement, instead of the last line, you can run: ```shell -ros2 launch robot_moveit circle_demo.launch.py +ros2 launch xcub_moveit_robot circle_demo.launch.py ``` and follow the instructions on the third shell you opened. @@ -228,10 +233,10 @@ You should have something like this: ### Controller performance -If you want to test the ros2_control `robot_controller` performance, you can rely to the `test_controller` package. It contains a simple script to sample the reaching space in front of iCub model. To run the simulation, please follow the first two steps described in the [Run the demos](#run-the-demos) section. After that, open another shell, source your workspace and then launch: +If you want to test the ros2_control `xcub_ros2_controllers` performance, you can rely to the `xcub_moveit_test_controller` package. It contains a simple script to sample the reaching space in front of iCub model. To run the simulation, please follow the first two steps described in the [Run the demos](#run-the-demos) section. After that, open another shell, source your workspace and then launch: ```shell -ros2 launch test_controller test_controller.launch.py +ros2 launch xcub_moveit_test_controller test_controller.launch.py ``` In this way, the test will start and the acquired data in terms of ideal and real poses are saved in two separated files in your current directory. Finally, you can plot them using the Matlab scripts provided in the `utils` folder. diff --git a/xcub_moveit2_all_packages/CMakeLists.txt b/xcub_moveit_all_packages/CMakeLists.txt similarity index 63% rename from xcub_moveit2_all_packages/CMakeLists.txt rename to xcub_moveit_all_packages/CMakeLists.txt index 59585ff..bbdb23c 100644 --- a/xcub_moveit2_all_packages/CMakeLists.txt +++ b/xcub_moveit_all_packages/CMakeLists.txt @@ -9,9 +9,9 @@ project(xcub-moveit2) # The order of inclusion was taken from colcon graph output add_subdirectory(../ergocub_moveit_config ${CMAKE_CURRENT_BINARY_DIR}/ergocub_moveit_config) -add_subdirectory(../grasp_moveit ${CMAKE_CURRENT_BINARY_DIR}/grasp_moveit) +add_subdirectory(../xcub_moveit_grasp ${CMAKE_CURRENT_BINARY_DIR}/xcub_moveit_grasp) add_subdirectory(../icub_moveit_config ${CMAKE_CURRENT_BINARY_DIR}/icub_moveit_config) -add_subdirectory(../robot_controller ${CMAKE_CURRENT_BINARY_DIR}/robot_controller) -add_subdirectory(../robot_moveit ${CMAKE_CURRENT_BINARY_DIR}/robot_moveit) -add_subdirectory(../test_controller ${CMAKE_CURRENT_BINARY_DIR}/test_controller) +add_subdirectory(../xcub_ros2_controllers ${CMAKE_CURRENT_BINARY_DIR}/xcub_ros2_controllers) +add_subdirectory(../xcub_moveit_robot ${CMAKE_CURRENT_BINARY_DIR}/xcub_moveit_robot) +add_subdirectory(../xcub_moveit_test_controller ${CMAKE_CURRENT_BINARY_DIR}/xcub_moveit_test_controller) diff --git a/xcub_moveit2_all_packages/COLCON_IGNORE b/xcub_moveit_all_packages/COLCON_IGNORE similarity index 100% rename from xcub_moveit2_all_packages/COLCON_IGNORE rename to xcub_moveit_all_packages/COLCON_IGNORE diff --git a/grasp_moveit/CMakeLists.txt b/xcub_moveit_grasp/CMakeLists.txt similarity index 98% rename from grasp_moveit/CMakeLists.txt rename to xcub_moveit_grasp/CMakeLists.txt index 778d798..1ef2305 100644 --- a/grasp_moveit/CMakeLists.txt +++ b/xcub_moveit_grasp/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.8) -project(grasp_moveit) +project(xcub_moveit_grasp) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) diff --git a/grasp_moveit/package.xml b/xcub_moveit_grasp/package.xml similarity index 96% rename from grasp_moveit/package.xml rename to xcub_moveit_grasp/package.xml index 3249118..bfb0d89 100644 --- a/grasp_moveit/package.xml +++ b/xcub_moveit_grasp/package.xml @@ -1,7 +1,7 @@ - grasp_moveit + xcub_moveit_grasp 0.0.0 ROS2 package for grasping task Martina Gloria diff --git a/grasp_moveit/src/grasp.cpp b/xcub_moveit_grasp/src/grasp.cpp similarity index 100% rename from grasp_moveit/src/grasp.cpp rename to xcub_moveit_grasp/src/grasp.cpp diff --git a/robot_moveit/CMakeLists.txt b/xcub_moveit_robot/CMakeLists.txt similarity index 83% rename from robot_moveit/CMakeLists.txt rename to xcub_moveit_robot/CMakeLists.txt index 223f561..04cd77f 100644 --- a/robot_moveit/CMakeLists.txt +++ b/xcub_moveit_robot/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.8) -project(robot_moveit) +project(xcub_moveit_robot) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) @@ -18,13 +18,13 @@ find_package(hardware_interface REQUIRED) find_package(yarp_control_msgs REQUIRED) find_package(YARP REQUIRED) -add_executable(robot_moveit src/robot_moveit.cpp launch/spawn_model.py) -target_include_directories(robot_moveit PUBLIC +add_executable(xcub_moveit_robot src/robot_moveit.cpp launch/spawn_model.py) +target_include_directories(xcub_moveit_robot PUBLIC $ $) -target_compile_features(robot_moveit PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 +target_compile_features(xcub_moveit_robot PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 ament_target_dependencies( - robot_moveit + xcub_moveit_robot "moveit_ros_planning_interface" "rclcpp" "rclpy" @@ -38,7 +38,7 @@ ament_target_dependencies( target_sources(${PROJECT_NAME} PRIVATE src/robot_moveit.cpp) target_link_libraries(${PROJECT_NAME} ${YARP_LIBRARIES}) -install(TARGETS robot_moveit DESTINATION lib/${PROJECT_NAME}) +install(TARGETS xcub_moveit_robot DESTINATION lib/${PROJECT_NAME}) install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) install(PROGRAMS launch/spawn_model.py DESTINATION lib/${PROJECT_NAME}) diff --git a/robot_moveit/launch/circle_demo.launch.py b/xcub_moveit_robot/launch/circle_demo.launch.py similarity index 90% rename from robot_moveit/launch/circle_demo.launch.py rename to xcub_moveit_robot/launch/circle_demo.launch.py index ab472be..8a28fa3 100644 --- a/robot_moveit/launch/circle_demo.launch.py +++ b/xcub_moveit_robot/launch/circle_demo.launch.py @@ -20,9 +20,9 @@ def generate_launch_description(): moveit_config = MoveItConfigsBuilder(robot_name).to_moveit_configs() circle_demo = Node( - name="robot_moveit", - package="robot_moveit", - executable="robot_moveit", + name="xcub_moveit_robot", + package="xcub_moveit_robot", + executable="xcub_moveit_robot", output="screen", parameters=[ moveit_config.robot_description, diff --git a/robot_moveit/launch/grasp_demo.launch.py b/xcub_moveit_robot/launch/grasp_demo.launch.py similarity index 93% rename from robot_moveit/launch/grasp_demo.launch.py rename to xcub_moveit_robot/launch/grasp_demo.launch.py index cb062d3..efc25b2 100644 --- a/robot_moveit/launch/grasp_demo.launch.py +++ b/xcub_moveit_robot/launch/grasp_demo.launch.py @@ -21,8 +21,8 @@ def generate_launch_description(): grasping_demo = Node( name="grasping", - package="grasp_moveit", - executable="grasp_moveit", + package="xcub_moveit_grasp", + executable="xcub_moveit_grasp", output="screen", parameters=[ moveit_config.robot_description, diff --git a/robot_moveit/launch/launch_icub.launch.py b/xcub_moveit_robot/launch/launch_icub.launch.py similarity index 100% rename from robot_moveit/launch/launch_icub.launch.py rename to xcub_moveit_robot/launch/launch_icub.launch.py diff --git a/robot_moveit/launch/robot.launch.py b/xcub_moveit_robot/launch/robot.launch.py similarity index 100% rename from robot_moveit/launch/robot.launch.py rename to xcub_moveit_robot/launch/robot.launch.py diff --git a/robot_moveit/launch/robot_controls.launch.py b/xcub_moveit_robot/launch/robot_controls.launch.py similarity index 83% rename from robot_moveit/launch/robot_controls.launch.py rename to xcub_moveit_robot/launch/robot_controls.launch.py index c3db551..d76d61a 100644 --- a/robot_moveit/launch/robot_controls.launch.py +++ b/xcub_moveit_robot/launch/robot_controls.launch.py @@ -5,6 +5,7 @@ from launch.actions import RegisterEventHandler from launch.event_handlers import OnProcessExit from ament_index_python.packages import get_package_share_directory +from launch.substitutions import PathJoinSubstitution def check_robot_name(): try: @@ -27,62 +28,64 @@ def generate_launch_description(): "config", "ros2_controllers.yaml", ) - + ros2_control_node = Node( package="controller_manager", executable="ros2_control_node", - parameters=[moveit_config.robot_description, ros2_controllers_path, - {"use_sim_time": False}], - output="log", + parameters=[ros2_controllers_path], + output="both", + remappings=[ + ("~/robot_description", "/robot_description"), + ], ) right_arm_torso_controller_spawner = Node( package="controller_manager", executable="spawner", arguments=["right_arm_torso_controller", "-c", "/controller_manager"], - parameters=[{"use_sim_time": False}], + parameters=[{"use_sim_time": True}], ) left_arm_controller_spawner = Node( package="controller_manager", executable="spawner", arguments=["left_arm_controller", "-c", "/controller_manager"], - parameters=[{"use_sim_time": False}], + parameters=[{"use_sim_time": True}], ) right_arm_controller_spawner = Node( package="controller_manager", executable="spawner", arguments=["right_arm_controller", "-c", "/controller_manager", "--inactive"], - parameters=[{"use_sim_time": False}], + parameters=[{"use_sim_time": True}], ) left_leg_controller_spawner = Node( package="controller_manager", executable="spawner", arguments=["left_leg_controller", "-c", "/controller_manager"], - parameters=[{"use_sim_time": False}], + parameters=[{"use_sim_time": True}], ) right_leg_controller_spawner = Node( package="controller_manager", executable="spawner", arguments=["right_leg_controller", "-c", "/controller_manager"], - parameters=[{"use_sim_time": False}], + parameters=[{"use_sim_time": True}], ) head_controller_spawner = Node( package="controller_manager", executable="spawner", arguments=["head_controller", "-c", "/controller_manager"], - parameters=[{"use_sim_time": False}], + parameters=[{"use_sim_time": True}], ) torso_controller_spawner = Node( package="controller_manager", executable="spawner", arguments=["torso_controller", "-c", "/controller_manager", "--inactive"], - parameters=[{"use_sim_time": False}], + parameters=[{"use_sim_time": True}], ) return LaunchDescription([ diff --git a/robot_moveit/launch/robot_sim.launch.py b/xcub_moveit_robot/launch/robot_sim.launch.py similarity index 92% rename from robot_moveit/launch/robot_sim.launch.py rename to xcub_moveit_robot/launch/robot_sim.launch.py index 4ac836e..5915409 100644 --- a/robot_moveit/launch/robot_sim.launch.py +++ b/xcub_moveit_robot/launch/robot_sim.launch.py @@ -43,7 +43,7 @@ def generate_launch_description(): PythonLaunchDescriptionSource([os.path.join(get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']) ) - moveit_config = ( + config = ( MoveItConfigsBuilder(robot_name) .robot_description(file_path="config/"+robot_name+".urdf.xacro") .robot_description_semantic(file_path="config/"+robot_name+".srdf") @@ -54,7 +54,7 @@ def generate_launch_description(): ) model_spawner = Node( - package='robot_moveit', + package='xcub_moveit_robot', executable='spawn_model.py', name='spawn_entity', output='screen', @@ -65,7 +65,7 @@ def generate_launch_description(): executable="robot_state_publisher", name="robot_state_publisher", output="both", - parameters=[moveit_config.robot_description, + parameters=[config.robot_description, {"use_sim_time": True}], ) @@ -108,9 +108,9 @@ def generate_launch_description(): package="moveit_ros_move_group", executable="move_group", output="screen", - parameters=[moveit_config.robot_description, + parameters=[config.robot_description, robot_description_semantic, - moveit_config.robot_description_kinematics, + config.robot_description_kinematics, ompl_planning_pipeline_config, moveit_controllers, trajectory_execution, @@ -126,10 +126,10 @@ def generate_launch_description(): name="rviz2", output="log", arguments=["-d", rviz_moveit], - parameters=[moveit_config.robot_description, + parameters=[config.robot_description, robot_description_semantic, - moveit_config.robot_description_kinematics, - moveit_config.planning_pipelines, + config.robot_description_kinematics, + config.planning_pipelines, ompl_planning_pipeline_config, planning_scene_monitor_parameters, {"use_sim_time": True}] diff --git a/robot_moveit/launch/spawn_model.py b/xcub_moveit_robot/launch/spawn_model.py similarity index 100% rename from robot_moveit/launch/spawn_model.py rename to xcub_moveit_robot/launch/spawn_model.py diff --git a/robot_moveit/package.xml b/xcub_moveit_robot/package.xml similarity index 96% rename from robot_moveit/package.xml rename to xcub_moveit_robot/package.xml index 0cf7e19..a392921 100644 --- a/robot_moveit/package.xml +++ b/xcub_moveit_robot/package.xml @@ -1,7 +1,7 @@ - robot_moveit + xcub_moveit_robot 0.0.0 TODO: Package description martinagloria diff --git a/robot_moveit/src/robot_moveit.cpp b/xcub_moveit_robot/src/robot_moveit.cpp similarity index 100% rename from robot_moveit/src/robot_moveit.cpp rename to xcub_moveit_robot/src/robot_moveit.cpp diff --git a/test_controller/CMakeLists.txt b/xcub_moveit_test_controller/CMakeLists.txt similarity index 94% rename from test_controller/CMakeLists.txt rename to xcub_moveit_test_controller/CMakeLists.txt index 8e4b489..4f539e4 100644 --- a/test_controller/CMakeLists.txt +++ b/xcub_moveit_test_controller/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.8) -project(test_controller) +project(xcub_moveit_test_controller) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) @@ -35,7 +35,7 @@ ament_target_dependencies( "hardware_interface" ) -target_sources(test_controller PRIVATE src/test_controller.cpp) +target_sources(xcub_moveit_test_controller PRIVATE src/test_controller.cpp) target_link_libraries(${PROJECT_NAME} ${YARP_LIBRARIES}) install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME}) diff --git a/test_controller/README.md b/xcub_moveit_test_controller/README.md similarity index 100% rename from test_controller/README.md rename to xcub_moveit_test_controller/README.md diff --git a/test_controller/launch/test_controller.launch.py b/xcub_moveit_test_controller/launch/test_controller.launch.py similarity index 81% rename from test_controller/launch/test_controller.launch.py rename to xcub_moveit_test_controller/launch/test_controller.launch.py index b2a2c09..c33ecbd 100644 --- a/test_controller/launch/test_controller.launch.py +++ b/xcub_moveit_test_controller/launch/test_controller.launch.py @@ -19,10 +19,10 @@ def generate_launch_description(): moveit_config = MoveItConfigsBuilder(robot_name).to_moveit_configs() - test_controller_node = Node( - name="test_controller", - package="test_controller", - executable="test_controller", + xcub_test_controller_node = Node( + name="xcub_moveit_test_controller", + package="xcub_moveit_test_controller", + executable="xcub_moveit_test_controller", output="screen", parameters=[ moveit_config.robot_description, @@ -33,5 +33,5 @@ def generate_launch_description(): ) return LaunchDescription([ - test_controller_node + xcub_test_controller_node ]) \ No newline at end of file diff --git a/test_controller/package.xml b/xcub_moveit_test_controller/package.xml similarity index 95% rename from test_controller/package.xml rename to xcub_moveit_test_controller/package.xml index 2327b7a..8aca0d4 100644 --- a/test_controller/package.xml +++ b/xcub_moveit_test_controller/package.xml @@ -1,7 +1,7 @@ - test_controller + xcub_moveit_test_controller 0.0.0 TODO: Package description martinagloria diff --git a/test_controller/src/test_controller.cpp b/xcub_moveit_test_controller/src/test_controller.cpp similarity index 98% rename from test_controller/src/test_controller.cpp rename to xcub_moveit_test_controller/src/test_controller.cpp index cfc6400..216add0 100644 --- a/test_controller/src/test_controller.cpp +++ b/xcub_moveit_test_controller/src/test_controller.cpp @@ -16,7 +16,7 @@ using namespace std::chrono_literals; -static const rclcpp::Logger LOGGER = rclcpp::get_logger("test_controller"); +static const rclcpp::Logger LOGGER = rclcpp::get_logger("xcub_test_controller"); int main(int argc, char** argv) { diff --git a/test_controller/utils/trac_ik_params_tuning.m b/xcub_moveit_test_controller/utils/trac_ik_params_tuning.m similarity index 100% rename from test_controller/utils/trac_ik_params_tuning.m rename to xcub_moveit_test_controller/utils/trac_ik_params_tuning.m diff --git a/test_controller/utils/workspace_estimation.m b/xcub_moveit_test_controller/utils/workspace_estimation.m similarity index 100% rename from test_controller/utils/workspace_estimation.m rename to xcub_moveit_test_controller/utils/workspace_estimation.m diff --git a/robot_controller/CMakeLists.txt b/xcub_ros2_controllers/CMakeLists.txt similarity index 98% rename from robot_controller/CMakeLists.txt rename to xcub_ros2_controllers/CMakeLists.txt index b4f7ddd..fae890f 100644 --- a/robot_controller/CMakeLists.txt +++ b/xcub_ros2_controllers/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.8) -project(robot_controller) +project(xcub_ros2_controllers) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) diff --git a/robot_controller/include/robot_controller/robot_controller.hpp b/xcub_ros2_controllers/include/robot_controller/robot_controller.hpp similarity index 100% rename from robot_controller/include/robot_controller/robot_controller.hpp rename to xcub_ros2_controllers/include/robot_controller/robot_controller.hpp diff --git a/robot_controller/include/robot_controller/visibility_control.h b/xcub_ros2_controllers/include/robot_controller/visibility_control.h similarity index 100% rename from robot_controller/include/robot_controller/visibility_control.h rename to xcub_ros2_controllers/include/robot_controller/visibility_control.h diff --git a/robot_controller/package.xml b/xcub_ros2_controllers/package.xml similarity index 96% rename from robot_controller/package.xml rename to xcub_ros2_controllers/package.xml index 0d1a7a9..42d7acb 100644 --- a/robot_controller/package.xml +++ b/xcub_ros2_controllers/package.xml @@ -1,7 +1,7 @@ - robot_controller + xcub_ros2_controllers 0.0.0 TODO: Package description martinagloria diff --git a/robot_controller/src/robot_controller.cpp b/xcub_ros2_controllers/src/robot_controller.cpp similarity index 100% rename from robot_controller/src/robot_controller.cpp rename to xcub_ros2_controllers/src/robot_controller.cpp diff --git a/robot_controller/robot_controller.xml b/xcub_ros2_controllers/xcub_ros2_controllers.xml similarity index 88% rename from robot_controller/robot_controller.xml rename to xcub_ros2_controllers/xcub_ros2_controllers.xml index 2093823..efe80d1 100644 --- a/robot_controller/robot_controller.xml +++ b/xcub_ros2_controllers/xcub_ros2_controllers.xml @@ -1,4 +1,4 @@ - +