From 61d9f0555645489159a424433f5faec4c3f6d815 Mon Sep 17 00:00:00 2001 From: Florian Walch <florian.walch@franka.de> Date: Fri, 15 Sep 2017 14:41:49 +0200 Subject: [PATCH] Rename franka_moveit_config to panda_moveit_config. --- README.md | 6 +- .../config/default_controllers.yaml | 70 ++++----- franka_control/config/franka_control.yaml | 16 +- franka_control/launch/franka_control.launch | 8 +- .../config/franka_example_controllers.yaml | 18 +-- .../cartesian_pose_example_controller.launch | 2 +- ...rtesian_velocity_example_controller.launch | 2 +- .../joint_impedance_example_controller.launch | 2 +- .../joint_position_example_controller.launch | 2 +- .../joint_velocity_example_controller.launch | 2 +- .../launch/model_example_controller.launch | 2 +- .../config/gripper_node_config.yaml | 4 +- franka_gripper/launch/franka_gripper.launch | 2 +- .../franka_hw_controller_switching_test.cpp | 4 +- franka_hw/test/launch/franka_hw_test.test | 2 +- .../config/fake_controllers.yaml | 23 --- franka_moveit_config/config/franka_emika.srdf | 137 ------------------ .../launch/franka_visualization.launch | 8 +- .../param/robot_read_settings.yaml | 14 +- .../.setup_assistant | 6 +- .../CMakeLists.txt | 2 +- .../config/fake_controllers.yaml | 23 +++ .../config/joint_limits.yaml | 18 +-- .../config/kinematics.yaml | 4 +- .../config/ompl_planning.yaml | 6 +- .../config/panda_arm_hand.srdf | 137 ++++++++++++++++++ .../launch/default_warehouse_db.launch | 4 +- .../launch/demo.launch | 10 +- .../fake_moveit_controller_manager.launch.xml | 2 +- .../launch/joystick_control.launch | 0 .../launch/move_group.launch | 14 +- .../launch/move_to_start.launch | 8 +- .../launch/moveit.rviz | 56 +++---- .../launch/moveit_rviz.launch | 6 +- .../launch/ompl_planning_pipeline.launch.xml | 2 +- .../launch/panda_moveit.launch | 4 +- ...panda_moveit_controller_manager.launch.xml | 0 .../panda_moveit_sensor_manager.launch.xml | 0 .../launch/planning_context.launch | 8 +- .../launch/planning_pipeline.launch.xml | 2 +- .../launch/run_benchmark_ompl.launch | 8 +- .../launch/sensor_manager.launch.xml | 4 +- .../launch/setup_assistant.launch | 2 +- .../launch/trajectory_execution.launch.xml | 4 +- .../launch/warehouse.launch | 2 +- .../launch/warehouse_settings.launch.xml | 0 .../mainpage.dox | 0 .../package.xml | 12 +- .../rosdoc.yaml | 0 .../scripts/move_to_start.py | 2 +- 50 files changed, 335 insertions(+), 335 deletions(-) delete mode 100644 franka_moveit_config/config/fake_controllers.yaml delete mode 100644 franka_moveit_config/config/franka_emika.srdf rename {franka_moveit_config => panda_moveit_config}/.setup_assistant (53%) rename {franka_moveit_config => panda_moveit_config}/CMakeLists.txt (90%) create mode 100644 panda_moveit_config/config/fake_controllers.yaml rename {franka_moveit_config => panda_moveit_config}/config/joint_limits.yaml (85%) rename {franka_moveit_config => panda_moveit_config}/config/kinematics.yaml (92%) rename {franka_moveit_config => panda_moveit_config}/config/ompl_planning.yaml (99%) create mode 100644 panda_moveit_config/config/panda_arm_hand.srdf rename {franka_moveit_config => panda_moveit_config}/launch/default_warehouse_db.launch (73%) rename {franka_moveit_config => panda_moveit_config}/launch/demo.launch (83%) rename {franka_moveit_config => panda_moveit_config}/launch/fake_moveit_controller_manager.launch.xml (78%) rename {franka_moveit_config => panda_moveit_config}/launch/joystick_control.launch (100%) rename {franka_moveit_config => panda_moveit_config}/launch/move_group.launch (79%) rename {franka_moveit_config => panda_moveit_config}/launch/move_to_start.launch (50%) rename {franka_moveit_config => panda_moveit_config}/launch/moveit.rviz (89%) rename {franka_moveit_config => panda_moveit_config}/launch/moveit_rviz.launch (75%) rename {franka_moveit_config => panda_moveit_config}/launch/ompl_planning_pipeline.launch.xml (91%) rename franka_moveit_config/launch/franka_moveit.launch => panda_moveit_config/launch/panda_moveit.launch (74%) rename franka_moveit_config/launch/franka_emika_moveit_controller_manager.launch.xml => panda_moveit_config/launch/panda_moveit_controller_manager.launch.xml (100%) rename franka_moveit_config/launch/franka_emika_moveit_sensor_manager.launch.xml => panda_moveit_config/launch/panda_moveit_sensor_manager.launch.xml (100%) rename {franka_moveit_config => panda_moveit_config}/launch/planning_context.launch (76%) rename {franka_moveit_config => panda_moveit_config}/launch/planning_pipeline.launch.xml (69%) rename {franka_moveit_config => panda_moveit_config}/launch/run_benchmark_ompl.launch (63%) rename {franka_moveit_config => panda_moveit_config}/launch/sensor_manager.launch.xml (72%) rename {franka_moveit_config => panda_moveit_config}/launch/setup_assistant.launch (75%) rename {franka_moveit_config => panda_moveit_config}/launch/trajectory_execution.launch.xml (85%) rename {franka_moveit_config => panda_moveit_config}/launch/warehouse.launch (83%) rename {franka_moveit_config => panda_moveit_config}/launch/warehouse_settings.launch.xml (100%) rename {franka_moveit_config => panda_moveit_config}/mainpage.dox (100%) rename {franka_moveit_config => panda_moveit_config}/package.xml (82%) rename {franka_moveit_config => panda_moveit_config}/rosdoc.yaml (100%) rename {franka_moveit_config => panda_moveit_config}/scripts/move_to_start.py (86%) diff --git a/README.md b/README.md index 69d3d51..2418d29 100644 --- a/README.md +++ b/README.md @@ -2,7 +2,7 @@ See the [FRANKA Control Interface documentation][fci-docs] for more information. -## MoveIt! quickstart +## MoveIt! quickstart for Panda research 1. Launch the joint trajectory controller @@ -10,8 +10,8 @@ See the [FRANKA Control Interface documentation][fci-docs] for more information. 2. Launch MoveIt! - roslaunch franka_moveit_config franka_moveit.launch + roslaunch panda_moveit_config panda_moveit.launch 3. Launch RViz - roslaunch franka_moveit_config moveit_rviz.launch + roslaunch panda_moveit_config moveit_rviz.launch diff --git a/franka_control/config/default_controllers.yaml b/franka_control/config/default_controllers.yaml index 6a24083..e3a3f94 100644 --- a/franka_control/config/default_controllers.yaml +++ b/franka_control/config/default_controllers.yaml @@ -1,64 +1,64 @@ position_joint_trajectory_controller: type: position_controllers/JointTrajectoryController joints: - - franka_emika_joint1 - - franka_emika_joint2 - - franka_emika_joint3 - - franka_emika_joint4 - - franka_emika_joint5 - - franka_emika_joint6 - - franka_emika_joint7 + - panda_joint1 + - panda_joint2 + - panda_joint3 + - panda_joint4 + - panda_joint5 + - panda_joint6 + - panda_joint7 constraints: goal_time: 0.5 - franka_emika_joint1: + panda_joint1: goal: 0.05 - franka_emika_joint2: + panda_joint2: goal: 0.05 - franka_emika_joint3: + panda_joint3: goal: 0.05 - franka_emika_joint4: + panda_joint4: goal: 0.05 - franka_emika_joint5: + panda_joint5: goal: 0.05 - franka_emika_joint6: + panda_joint6: goal: 0.05 - franka_emika_joint7: + panda_joint7: goal: 0.05 effort_joint_trajectory_controller: type: effort_controllers/JointTrajectoryController joints: - - franka_emika_joint1 - - franka_emika_joint2 - - franka_emika_joint3 - - franka_emika_joint4 - - franka_emika_joint5 - - franka_emika_joint6 - - franka_emika_joint7 + - panda_joint1 + - panda_joint2 + - panda_joint3 + - panda_joint4 + - panda_joint5 + - panda_joint6 + - panda_joint7 constraints: goal_time: 0.5 - franka_emika_joint1: + panda_joint1: goal: 0.05 - franka_emika_joint2: + panda_joint2: goal: 0.05 - franka_emika_joint3: + panda_joint3: goal: 0.05 - franka_emika_joint4: + panda_joint4: goal: 0.05 - franka_emika_joint5: + panda_joint5: goal: 0.05 - franka_emika_joint6: + panda_joint6: goal: 0.05 - franka_emika_joint7: + panda_joint7: goal: 0.05 gains: - franka_emika_joint1: {p: 100, d: 10, i: 0, i_clamp: 1} - franka_emika_joint2: {p: 100, d: 10, i: 0, i_clamp: 1} - franka_emika_joint3: {p: 100, d: 10, i: 0, i_clamp: 1} - franka_emika_joint4: {p: 100, d: 10, i: 0, i_clamp: 1} - franka_emika_joint5: {p: 100, d: 10, i: 0, i_clamp: 1} - franka_emika_joint6: {p: 100, d: 10, i: 0, i_clamp: 1} - franka_emika_joint7: {p: 100, d: 10, i: 0, i_clamp: 1} + panda_joint1: {p: 100, d: 10, i: 0, i_clamp: 1} + panda_joint2: {p: 100, d: 10, i: 0, i_clamp: 1} + panda_joint3: {p: 100, d: 10, i: 0, i_clamp: 1} + panda_joint4: {p: 100, d: 10, i: 0, i_clamp: 1} + panda_joint5: {p: 100, d: 10, i: 0, i_clamp: 1} + panda_joint6: {p: 100, d: 10, i: 0, i_clamp: 1} + panda_joint7: {p: 100, d: 10, i: 0, i_clamp: 1} franka_state_controller: type: franka_control/FrankaStateController diff --git a/franka_control/config/franka_control.yaml b/franka_control/config/franka_control.yaml index b8f7795..52e2e28 100644 --- a/franka_control/config/franka_control.yaml +++ b/franka_control/config/franka_control.yaml @@ -1,11 +1,11 @@ joint_names: - - franka_emika_joint1 - - franka_emika_joint2 - - franka_emika_joint3 - - franka_emika_joint4 - - franka_emika_joint5 - - franka_emika_joint6 - - franka_emika_joint7 + - panda_joint1 + - panda_joint2 + - panda_joint3 + - panda_joint4 + - panda_joint5 + - panda_joint6 + - panda_joint7 -arm_id: franka_emika +arm_id: panda robot_ip: 127.0.0.1 diff --git a/franka_control/launch/franka_control.launch b/franka_control/launch/franka_control.launch index 2313431..11098d3 100644 --- a/franka_control/launch/franka_control.launch +++ b/franka_control/launch/franka_control.launch @@ -1,15 +1,15 @@ <?xml version="1.0" ?> <launch> <arg name="robot_ip" default="robot.franka.de" /> - <arg name="arm_id" default="franka_emika" /> + <arg name="arm_id" default="panda" /> <arg name="load_gripper" default="true" /> <node name="$(arg arm_id)" pkg="franka_control" type="franka_control_node" output="screen" required="true"> <rosparam command="load" file="$(find franka_control)/config/franka_control.yaml" /> <param name="robot_ip" value="$(arg robot_ip)" /> <param name="arm_id" value="$(arg arm_id)" /> - <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/FEA_01_01_Gripper.urdf.xacro'" if="$(arg load_gripper)" /> - <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/FEA_01_01.urdf.xacro'" unless="$(arg load_gripper)" /> + <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'" if="$(arg load_gripper)" /> + <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm.urdf.xacro'" unless="$(arg load_gripper)" /> </node> <group ns="$(arg arm_id)"> @@ -17,7 +17,7 @@ <node name="state_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="franka_state_controller --shutdown-timeout 2"/> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen"/> <node name="joint_state_publisher" type="joint_state_publisher" pkg="joint_state_publisher" output="screen"> - <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/FEA_01_01_Gripper.urdf.xacro'" /> + <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'" /> <rosparam if="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states, franka_gripper_node/joint_states] </rosparam> <rosparam unless="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states] </rosparam> <param name="rate" value="30"/> diff --git a/franka_example_controllers/config/franka_example_controllers.yaml b/franka_example_controllers/config/franka_example_controllers.yaml index 292cf83..699fea4 100644 --- a/franka_example_controllers/config/franka_example_controllers.yaml +++ b/franka_example_controllers/config/franka_example_controllers.yaml @@ -12,19 +12,19 @@ cartesian_velocity_example_controller: model_example_controller: type: franka_example_controllers/ModelExampleController - arm_id: franka_emika + arm_id: panda joint_impedance_example_controller: type: franka_example_controllers/JointImpedanceExampleController - arm_id: franka_emika + arm_id: panda joint_names: - - franka_emika_joint1 - - franka_emika_joint2 - - franka_emika_joint3 - - franka_emika_joint4 - - franka_emika_joint5 - - franka_emika_joint6 - - franka_emika_joint7 + - panda_joint1 + - panda_joint2 + - panda_joint3 + - panda_joint4 + - panda_joint5 + - panda_joint6 + - panda_joint7 k_gains: - 1000.0 - 1000.0 diff --git a/franka_example_controllers/launch/cartesian_pose_example_controller.launch b/franka_example_controllers/launch/cartesian_pose_example_controller.launch index a627508..0b07cb3 100644 --- a/franka_example_controllers/launch/cartesian_pose_example_controller.launch +++ b/franka_example_controllers/launch/cartesian_pose_example_controller.launch @@ -1,7 +1,7 @@ <?xml version="1.0" ?> <launch> <arg name="robot_ip" default="robot.franka.de" /> - <arg name="arm_id" value="franka_emika" /> + <arg name="arm_id" value="panda" /> <arg name="load_gripper" default="true" /> <include file="$(find franka_hw)/launch/franka_hw.launch" > <arg name="robot_ip" value="$(arg robot_ip)" /> diff --git a/franka_example_controllers/launch/cartesian_velocity_example_controller.launch b/franka_example_controllers/launch/cartesian_velocity_example_controller.launch index 58a0ac2..ea9f7b0 100644 --- a/franka_example_controllers/launch/cartesian_velocity_example_controller.launch +++ b/franka_example_controllers/launch/cartesian_velocity_example_controller.launch @@ -1,7 +1,7 @@ <?xml version="1.0" ?> <launch> <arg name="robot_ip" default="robot.franka.de" /> - <arg name="arm_id" value="franka_emika" /> + <arg name="arm_id" value="panda" /> <arg name="load_gripper" default="true" /> <include file="$(find franka_hw)/launch/franka_hw.launch" > <arg name="robot_ip" value="$(arg robot_ip)" /> diff --git a/franka_example_controllers/launch/joint_impedance_example_controller.launch b/franka_example_controllers/launch/joint_impedance_example_controller.launch index 3334e76..a676caf 100644 --- a/franka_example_controllers/launch/joint_impedance_example_controller.launch +++ b/franka_example_controllers/launch/joint_impedance_example_controller.launch @@ -1,7 +1,7 @@ <?xml version="1.0" ?> <launch> <arg name="robot_ip" default="robot.franka.de" /> - <arg name="arm_id" value="franka_emika" /> + <arg name="arm_id" value="panda" /> <arg name="load_gripper" default="true" /> <include file="$(find franka_hw)/launch/franka_hw.launch" > <arg name="robot_ip" value="$(arg robot_ip)" /> diff --git a/franka_example_controllers/launch/joint_position_example_controller.launch b/franka_example_controllers/launch/joint_position_example_controller.launch index fdab138..d1f9d60 100644 --- a/franka_example_controllers/launch/joint_position_example_controller.launch +++ b/franka_example_controllers/launch/joint_position_example_controller.launch @@ -1,7 +1,7 @@ <?xml version="1.0" ?> <launch> <arg name="robot_ip" default="robot.franka.de" /> - <arg name="arm_id" value="franka_emika" /> + <arg name="arm_id" value="panda" /> <arg name="load_gripper" default="true" /> <include file="$(find franka_hw)/launch/franka_hw.launch" > <arg name="robot_ip" value="$(arg robot_ip)" /> diff --git a/franka_example_controllers/launch/joint_velocity_example_controller.launch b/franka_example_controllers/launch/joint_velocity_example_controller.launch index 4c4c244..e8e2412 100644 --- a/franka_example_controllers/launch/joint_velocity_example_controller.launch +++ b/franka_example_controllers/launch/joint_velocity_example_controller.launch @@ -1,7 +1,7 @@ <?xml version="1.0" ?> <launch> <arg name="robot_ip" default="robot.franka.de" /> - <arg name="arm_id" value="franka_emika" /> + <arg name="arm_id" value="panda" /> <arg name="load_gripper" default="true" /> <include file="$(find franka_hw)/launch/franka_hw.launch" > <arg name="robot_ip" value="$(arg robot_ip)" /> diff --git a/franka_example_controllers/launch/model_example_controller.launch b/franka_example_controllers/launch/model_example_controller.launch index 8804c46..ab19ad0 100644 --- a/franka_example_controllers/launch/model_example_controller.launch +++ b/franka_example_controllers/launch/model_example_controller.launch @@ -1,7 +1,7 @@ <?xml version="1.0" ?> <launch> <arg name="robot_ip" default="robot.franka.de" /> - <arg name="arm_id" value="franka_emika" /> + <arg name="arm_id" value="panda" /> <arg name="load_gripper" default="true" /> <include file="$(find franka_hw)/launch/franka_hw.launch" > <arg name="robot_ip" value="$(arg robot_ip)" /> diff --git a/franka_gripper/config/gripper_node_config.yaml b/franka_gripper/config/gripper_node_config.yaml index eb375d8..20223f2 100644 --- a/franka_gripper/config/gripper_node_config.yaml +++ b/franka_gripper/config/gripper_node_config.yaml @@ -1,6 +1,6 @@ publish_rate: 30 # [Hz] joint_names: - - franka_emika_finger_joint1 - - franka_emika_finger_joint2 + - panda_finger_joint1 + - panda_finger_joint2 width_tolerance: 0.01 # [m] default_speed: 0.1 # [m/s] \ No newline at end of file diff --git a/franka_gripper/launch/franka_gripper.launch b/franka_gripper/launch/franka_gripper.launch index 3580cb0..d990574 100644 --- a/franka_gripper/launch/franka_gripper.launch +++ b/franka_gripper/launch/franka_gripper.launch @@ -1,7 +1,7 @@ <?xml version="1.0" ?> <launch> <arg name="robot_ip" default="robot.franka.de" /> - <arg name="arm_id" default="franka_emika" /> + <arg name="arm_id" default="panda" /> <group ns="$(arg arm_id)"> <node name="franka_gripper_node" pkg="franka_gripper" type="franka_gripper_node" output="screen"> <param name="robot_ip" value="$(arg robot_ip)"/> diff --git a/franka_hw/test/franka_hw_controller_switching_test.cpp b/franka_hw/test/franka_hw_controller_switching_test.cpp index 4fe9571..be2b72a 100644 --- a/franka_hw/test/franka_hw_controller_switching_test.cpp +++ b/franka_hw/test/franka_hw_controller_switching_test.cpp @@ -21,7 +21,7 @@ using std::set; using hardware_interface::InterfaceResources; using hardware_interface::ControllerInfo; -std::string arm_id("franka_emika"); +std::string arm_id("panda"); std::array<std::string, 7> joint_names = {arm_id + "_joint1", arm_id + "_joint2", arm_id + "_joint3", @@ -93,7 +93,7 @@ public: std::unique_ptr<FrankaHW> robot_; }; -string arm_id2("franka_emika2"); +string arm_id2("panda2"); string jp_iface_str("hardware_interface::PositionJointInterface"); string jv_iface_str("hardware_interface::VelocityJointInterface"); string jt_iface_str("hardware_interface::EffortJointInterface"); diff --git a/franka_hw/test/launch/franka_hw_test.test b/franka_hw/test/launch/franka_hw_test.test index 8c606a2..53dfa12 100644 --- a/franka_hw/test/launch/franka_hw_test.test +++ b/franka_hw/test/launch/franka_hw_test.test @@ -1,5 +1,5 @@ <launch> <env name="ROSCONSOLE_CONFIG_FILE" value="$(find franka_hw)/test/config/ros_console_settings_for_tests.conf"/> - <param name="robot_description" command="$(find xacro)/xacro --inorder $(find franka_description)/robots/panda_01_01.urdf.xacro" /> + <param name="robot_description" command="$(find xacro)/xacro --inorder $(find franka_description)/robots/panda_arm.urdf.xacro" /> <test test-name="franka_hw_test" pkg="franka_hw" type="franka_hw_test" /> </launch> diff --git a/franka_moveit_config/config/fake_controllers.yaml b/franka_moveit_config/config/fake_controllers.yaml deleted file mode 100644 index 6e42dd2..0000000 --- a/franka_moveit_config/config/fake_controllers.yaml +++ /dev/null @@ -1,23 +0,0 @@ -controller_list: - - name: fake_franka_controller - joints: - - franka_emika_joint1 - - franka_emika_joint2 - - franka_emika_joint3 - - franka_emika_joint4 - - franka_emika_joint5 - - franka_emika_joint6 - - franka_emika_joint7 - - name: fake_franka_with_gripper_controller - joints: - - franka_emika_joint1 - - franka_emika_joint2 - - franka_emika_joint3 - - franka_emika_joint4 - - franka_emika_joint5 - - franka_emika_joint6 - - franka_emika_joint7 - - name: fake_franka_gripper_controller - joints: - - franka_emika_finger_joint1 - - franka_emika_finger_joint2 diff --git a/franka_moveit_config/config/franka_emika.srdf b/franka_moveit_config/config/franka_emika.srdf deleted file mode 100644 index 5a93cec..0000000 --- a/franka_moveit_config/config/franka_emika.srdf +++ /dev/null @@ -1,137 +0,0 @@ -<?xml version="1.0" ?> -<!--This does not replace URDF, and is not an extension of URDF. - This is a format for representing semantic information about the robot structure. - A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined ---> -<robot name="franka_emika"> - <!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc--> - <!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included--> - <!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included--> - <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group--> - <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names--> - <group name="franka"> - <link name="franka_emika_link0" /> - <link name="franka_emika_link1" /> - <link name="franka_emika_link2" /> - <link name="franka_emika_link3" /> - <link name="franka_emika_link4" /> - <link name="franka_emika_link5" /> - <link name="franka_emika_link6" /> - <link name="franka_emika_link7" /> - <link name="franka_emika_link8" /> - <joint name="franka_emika_joint1" /> - <joint name="franka_emika_joint2" /> - <joint name="franka_emika_joint3" /> - <joint name="franka_emika_joint4" /> - <joint name="franka_emika_joint5" /> - <joint name="franka_emika_joint6" /> - <joint name="franka_emika_joint7" /> - <joint name="franka_emika_joint8" /> - <chain base_link="franka_emika_link0" tip_link="franka_emika_link8" /> - </group> - <group name="franka_with_gripper"> - <link name="franka_emika_link0" /> - <link name="franka_emika_link1" /> - <link name="franka_emika_link2" /> - <link name="franka_emika_link3" /> - <link name="franka_emika_link4" /> - <link name="franka_emika_link5" /> - <link name="franka_emika_link6" /> - <link name="franka_emika_link7" /> - <link name="franka_emika_link8" /> - <link name="franka_emika_hand" /> - <joint name="franka_emika_joint1" /> - <joint name="franka_emika_joint2" /> - <joint name="franka_emika_joint3" /> - <joint name="franka_emika_joint4" /> - <joint name="franka_emika_joint5" /> - <joint name="franka_emika_joint6" /> - <joint name="franka_emika_joint7" /> - <joint name="franka_emika_joint8" /> - <joint name="franka_emika_hand_joint" /> - <chain base_link="franka_emika_link0" tip_link="franka_emika_hand" /> - </group> - <group name="franka_gripper"> - <link name="franka_emika_hand" /> - <link name="franka_emika_leftfinger" /> - <link name="franka_emika_rightfinger" /> - <joint name="franka_emika_finger_joint1" /> - <joint name="franka_emika_finger_joint2" /> - </group> - <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> - <group_state name="zero" group="franka"> - <joint name="franka_emika_joint1" value="0" /> - <joint name="franka_emika_joint2" value="0" /> - <joint name="franka_emika_joint3" value="0" /> - <joint name="franka_emika_joint4" value="0" /> - <joint name="franka_emika_joint5" value="0" /> - <joint name="franka_emika_joint6" value="0" /> - <joint name="franka_emika_joint7" value="0" /> - </group_state> - <group_state name="ready" group="franka"> - <joint name="franka_emika_joint1" value="0" /> - <joint name="franka_emika_joint2" value="-0.2128" /> - <joint name="franka_emika_joint3" value="0" /> - <joint name="franka_emika_joint4" value="-1.928" /> - <joint name="franka_emika_joint5" value="0" /> - <joint name="franka_emika_joint6" value="1.7741" /> - <joint name="franka_emika_joint7" value="0" /> - </group_state> - <group_state name="home_hand" group="franka_with_gripper"> - <joint name="franka_emika_joint1" value="0" /> - <joint name="franka_emika_joint2" value="0" /> - <joint name="franka_emika_joint3" value="0" /> - <joint name="franka_emika_joint4" value="0" /> - <joint name="franka_emika_joint5" value="0" /> - <joint name="franka_emika_joint6" value="0" /> - <joint name="franka_emika_joint7" value="0.7918" /> - </group_state> - <group_state name="ready_hand" group="franka_with_gripper"> - <joint name="franka_emika_joint1" value="0" /> - <joint name="franka_emika_joint2" value="-0.3912" /> - <joint name="franka_emika_joint3" value="0" /> - <joint name="franka_emika_joint4" value="-1.9161" /> - <joint name="franka_emika_joint5" value="0" /> - <joint name="franka_emika_joint6" value="1.5029" /> - <joint name="franka_emika_joint7" value="0.7918" /> - </group_state> - <!--END EFFECTOR: Purpose: Represent information about an end effector.--> - <end_effector name="franka_gripper" parent_link="franka_emika_hand" group="franka_gripper" parent_group="franka_with_gripper" /> - <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. --> - <disable_collisions link1="franka_emika_hand" link2="franka_emika_leftfinger" reason="Adjacent" /> - <disable_collisions link1="franka_emika_hand" link2="franka_emika_link3" reason="Never" /> - <disable_collisions link1="franka_emika_hand" link2="franka_emika_link4" reason="Never" /> - <disable_collisions link1="franka_emika_hand" link2="franka_emika_link5" reason="Default" /> - <disable_collisions link1="franka_emika_hand" link2="franka_emika_link6" reason="Never" /> - <disable_collisions link1="franka_emika_hand" link2="franka_emika_link7" reason="Adjacent" /> - <disable_collisions link1="franka_emika_hand" link2="franka_emika_rightfinger" reason="Adjacent" /> - <disable_collisions link1="franka_emika_leftfinger" link2="franka_emika_link3" reason="Never" /> - <disable_collisions link1="franka_emika_leftfinger" link2="franka_emika_link4" reason="Never" /> - <disable_collisions link1="franka_emika_leftfinger" link2="franka_emika_link6" reason="Never" /> - <disable_collisions link1="franka_emika_leftfinger" link2="franka_emika_link7" reason="Never" /> - <disable_collisions link1="franka_emika_leftfinger" link2="franka_emika_rightfinger" reason="Default" /> - <disable_collisions link1="franka_emika_link0" link2="franka_emika_link1" reason="Adjacent" /> - <disable_collisions link1="franka_emika_link0" link2="franka_emika_link2" reason="Never" /> - <disable_collisions link1="franka_emika_link0" link2="franka_emika_link3" reason="Never" /> - <disable_collisions link1="franka_emika_link0" link2="franka_emika_link4" reason="Never" /> - <disable_collisions link1="franka_emika_link1" link2="franka_emika_link2" reason="Adjacent" /> - <disable_collisions link1="franka_emika_link1" link2="franka_emika_link3" reason="Never" /> - <disable_collisions link1="franka_emika_link1" link2="franka_emika_link4" reason="Never" /> - <disable_collisions link1="franka_emika_link2" link2="franka_emika_link3" reason="Adjacent" /> - <disable_collisions link1="franka_emika_link2" link2="franka_emika_link4" reason="Never" /> - <disable_collisions link1="franka_emika_link2" link2="franka_emika_link6" reason="Never" /> - <disable_collisions link1="franka_emika_link3" link2="franka_emika_link4" reason="Adjacent" /> - <disable_collisions link1="franka_emika_link3" link2="franka_emika_link5" reason="Never" /> - <disable_collisions link1="franka_emika_link3" link2="franka_emika_link6" reason="Never" /> - <disable_collisions link1="franka_emika_link3" link2="franka_emika_link7" reason="Never" /> - <disable_collisions link1="franka_emika_link3" link2="franka_emika_rightfinger" reason="Never" /> - <disable_collisions link1="franka_emika_link4" link2="franka_emika_link5" reason="Adjacent" /> - <disable_collisions link1="franka_emika_link4" link2="franka_emika_link6" reason="Never" /> - <disable_collisions link1="franka_emika_link4" link2="franka_emika_link7" reason="Never" /> - <disable_collisions link1="franka_emika_link4" link2="franka_emika_rightfinger" reason="Never" /> - <disable_collisions link1="franka_emika_link5" link2="franka_emika_link6" reason="Adjacent" /> - <disable_collisions link1="franka_emika_link5" link2="franka_emika_link7" reason="Default" /> - <disable_collisions link1="franka_emika_link6" link2="franka_emika_link7" reason="Adjacent" /> - <disable_collisions link1="franka_emika_link6" link2="franka_emika_rightfinger" reason="Never" /> - <disable_collisions link1="franka_emika_link7" link2="franka_emika_rightfinger" reason="Never" /> -</robot> diff --git a/franka_visualization/launch/franka_visualization.launch b/franka_visualization/launch/franka_visualization.launch index ca829a2..99fe15a 100644 --- a/franka_visualization/launch/franka_visualization.launch +++ b/franka_visualization/launch/franka_visualization.launch @@ -4,15 +4,15 @@ <arg name="load_gripper" default="true" /> <arg name="robot_ip" default="robot.franka.de" /> - <param unless="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder $(find franka_description)/robots/FEA_01_01.urdf.xacro" /> - <param if="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder $(find franka_description)/robots/FEA_01_01_Gripper.urdf.xacro" /> + <param unless="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder $(find franka_description)/robots/panda_arm.urdf.xacro" /> + <param if="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder $(find franka_description)/robots/panda_arm_hand.urdf.xacro" /> <node name="franka_joint_state_publisher" pkg="franka_visualization" type="franka_joint_state_publisher" output="screen"> <rosparam command="load" file="$(find franka_visualization)/param/robot_read_settings.yaml" /> <param name="robot_ip" value="$(arg robot_ip)" /> </node> <node name="joint_state_publisher" type="joint_state_publisher" pkg="joint_state_publisher" output="screen"> - <param if="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/FEA_01_01_Gripper.urdf.xacro'" /> - <param unless="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/FEA_01_01.urdf.xacro'" /> + <param if="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'" /> + <param unless="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm.urdf.xacro'" /> <rosparam param="source_list">[franka_joint_state_publisher/joint_states] </rosparam> <param if="$(arg load_gripper)" name="publish_default_positions" value="true" /> </node> diff --git a/franka_visualization/param/robot_read_settings.yaml b/franka_visualization/param/robot_read_settings.yaml index a2b6f4f..2c1154d 100644 --- a/franka_visualization/param/robot_read_settings.yaml +++ b/franka_visualization/param/robot_read_settings.yaml @@ -1,9 +1,9 @@ joint_names: - - franka_emika_joint1 - - franka_emika_joint2 - - franka_emika_joint3 - - franka_emika_joint4 - - franka_emika_joint5 - - franka_emika_joint6 - - franka_emika_joint7 + - panda_joint1 + - panda_joint2 + - panda_joint3 + - panda_joint4 + - panda_joint5 + - panda_joint6 + - panda_joint7 diff --git a/franka_moveit_config/.setup_assistant b/panda_moveit_config/.setup_assistant similarity index 53% rename from franka_moveit_config/.setup_assistant rename to panda_moveit_config/.setup_assistant index 4fe299f..2388fcc 100644 --- a/franka_moveit_config/.setup_assistant +++ b/panda_moveit_config/.setup_assistant @@ -1,10 +1,10 @@ moveit_setup_assistant_config: URDF: package: franka_description - relative_path: robots/FEA_01_01_Gripper.urdf.xacro + relative_path: robots/panda_arm_hand.urdf.xacro SRDF: - relative_path: config/franka_emika.srdf + relative_path: config/panda_arm_hand.srdf CONFIG: author_name: Franka Emika GmbH author_email: info@franka.de - generated_timestamp: 1501848099 \ No newline at end of file + generated_timestamp: 1501848099 diff --git a/franka_moveit_config/CMakeLists.txt b/panda_moveit_config/CMakeLists.txt similarity index 90% rename from franka_moveit_config/CMakeLists.txt rename to panda_moveit_config/CMakeLists.txt index 78fde91..b4e880c 100644 --- a/franka_moveit_config/CMakeLists.txt +++ b/panda_moveit_config/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 2.8.3) -project(franka_moveit_config) +project(panda_moveit_config) find_package(catkin REQUIRED) diff --git a/panda_moveit_config/config/fake_controllers.yaml b/panda_moveit_config/config/fake_controllers.yaml new file mode 100644 index 0000000..34a8e37 --- /dev/null +++ b/panda_moveit_config/config/fake_controllers.yaml @@ -0,0 +1,23 @@ +controller_list: + - name: fake_panda_controller + joints: + - panda_joint1 + - panda_joint2 + - panda_joint3 + - panda_joint4 + - panda_joint5 + - panda_joint6 + - panda_joint7 + - name: fake_panda_arm_hand_controller + joints: + - panda_joint1 + - panda_joint2 + - panda_joint3 + - panda_joint4 + - panda_joint5 + - panda_joint6 + - panda_joint7 + - name: fake_hand_controller + joints: + - panda_finger_joint1 + - panda_finger_joint2 diff --git a/franka_moveit_config/config/joint_limits.yaml b/panda_moveit_config/config/joint_limits.yaml similarity index 85% rename from franka_moveit_config/config/joint_limits.yaml rename to panda_moveit_config/config/joint_limits.yaml index b263b5c..4323784 100644 --- a/franka_moveit_config/config/joint_limits.yaml +++ b/panda_moveit_config/config/joint_limits.yaml @@ -2,47 +2,47 @@ # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] joint_limits: - franka_emika_finger_joint1: + panda_finger_joint1: has_velocity_limits: true max_velocity: 0.3 has_acceleration_limits: true max_acceleration: 0.5 - franka_emika_finger_joint2: + panda_finger_joint2: has_velocity_limits: true max_velocity: 0.3 has_acceleration_limits: true max_acceleration: 0.5 - franka_emika_joint1: + panda_joint1: has_velocity_limits: true max_velocity: 0.5 has_acceleration_limits: true max_acceleration: 0.5 - franka_emika_joint2: + panda_joint2: has_velocity_limits: true max_velocity: 0.5 has_acceleration_limits: true max_acceleration: 0.5 - franka_emika_joint3: + panda_joint3: has_velocity_limits: true max_velocity: 0.5 has_acceleration_limits: true max_acceleration: 0.5 - franka_emika_joint4: + panda_joint4: has_velocity_limits: true max_velocity: 0.5 has_acceleration_limits: true max_acceleration: 0.5 - franka_emika_joint5: + panda_joint5: has_velocity_limits: true max_velocity: 0.5 has_acceleration_limits: true max_acceleration: 0.5 - franka_emika_joint6: + panda_joint6: has_velocity_limits: true max_velocity: 0.5 has_acceleration_limits: true max_acceleration: 0.5 - franka_emika_joint7: + panda_joint7: has_velocity_limits: true max_velocity: 0.5 has_acceleration_limits: true diff --git a/franka_moveit_config/config/kinematics.yaml b/panda_moveit_config/config/kinematics.yaml similarity index 92% rename from franka_moveit_config/config/kinematics.yaml rename to panda_moveit_config/config/kinematics.yaml index 1ddcc0c..c64ffe3 100644 --- a/franka_moveit_config/config/kinematics.yaml +++ b/panda_moveit_config/config/kinematics.yaml @@ -1,9 +1,9 @@ -franka: +panda: kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver_search_resolution: 0.005 kinematics_solver_timeout: 0.005 kinematics_solver_attempts: 3 -franka_with_gripper: +panda_arm_hand: kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver_search_resolution: 0.005 kinematics_solver_timeout: 0.005 diff --git a/franka_moveit_config/config/ompl_planning.yaml b/panda_moveit_config/config/ompl_planning.yaml similarity index 99% rename from franka_moveit_config/config/ompl_planning.yaml rename to panda_moveit_config/config/ompl_planning.yaml index 53acaa0..9251f54 100644 --- a/franka_moveit_config/config/ompl_planning.yaml +++ b/panda_moveit_config/config/ompl_planning.yaml @@ -120,7 +120,7 @@ planner_configs: sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 max_failures: 5000 # maximum consecutive failure limit. default: 5000 -franka: +panda: planner_configs: - SBLkConfigDefault - ESTkConfigDefault @@ -145,7 +145,7 @@ franka: - LazyPRMstarkConfigDefault - SPARSkConfigDefault - SPARStwokConfigDefault -franka_with_gripper: +panda_arm_hand: planner_configs: - SBLkConfigDefault - ESTkConfigDefault @@ -170,7 +170,7 @@ franka_with_gripper: - LazyPRMstarkConfigDefault - SPARSkConfigDefault - SPARStwokConfigDefault -franka_gripper: +hand: planner_configs: - SBLkConfigDefault - ESTkConfigDefault diff --git a/panda_moveit_config/config/panda_arm_hand.srdf b/panda_moveit_config/config/panda_arm_hand.srdf new file mode 100644 index 0000000..d7697ec --- /dev/null +++ b/panda_moveit_config/config/panda_arm_hand.srdf @@ -0,0 +1,137 @@ +<?xml version="1.0" ?> +<!--This does not replace URDF, and is not an extension of URDF. + This is a format for representing semantic information about the robot structure. + A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined +--> +<robot name="panda"> + <!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc--> + <!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included--> + <!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included--> + <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group--> + <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names--> + <group name="panda_arm"> + <link name="panda_link0" /> + <link name="panda_link1" /> + <link name="panda_link2" /> + <link name="panda_link3" /> + <link name="panda_link4" /> + <link name="panda_link5" /> + <link name="panda_link6" /> + <link name="panda_link7" /> + <link name="panda_link8" /> + <joint name="panda_joint1" /> + <joint name="panda_joint2" /> + <joint name="panda_joint3" /> + <joint name="panda_joint4" /> + <joint name="panda_joint5" /> + <joint name="panda_joint6" /> + <joint name="panda_joint7" /> + <joint name="panda_joint8" /> + <chain base_link="panda_link0" tip_link="panda_link8" /> + </group> + <group name="panda_arm_hand"> + <link name="panda_link0" /> + <link name="panda_link1" /> + <link name="panda_link2" /> + <link name="panda_link3" /> + <link name="panda_link4" /> + <link name="panda_link5" /> + <link name="panda_link6" /> + <link name="panda_link7" /> + <link name="panda_link8" /> + <link name="panda_hand" /> + <joint name="panda_joint1" /> + <joint name="panda_joint2" /> + <joint name="panda_joint3" /> + <joint name="panda_joint4" /> + <joint name="panda_joint5" /> + <joint name="panda_joint6" /> + <joint name="panda_joint7" /> + <joint name="panda_joint8" /> + <joint name="panda_hand_joint" /> + <chain base_link="panda_link0" tip_link="panda_hand" /> + </group> + <group name="hand"> + <link name="panda_hand" /> + <link name="panda_leftfinger" /> + <link name="panda_rightfinger" /> + <joint name="panda_finger_joint1" /> + <joint name="panda_finger_joint2" /> + </group> + <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> + <group_state name="home" group="panda_arm"> + <joint name="panda_joint1" value="0" /> + <joint name="panda_joint2" value="0" /> + <joint name="panda_joint3" value="0" /> + <joint name="panda_joint4" value="0" /> + <joint name="panda_joint5" value="0" /> + <joint name="panda_joint6" value="0" /> + <joint name="panda_joint7" value="0" /> + </group_state> + <group_state name="ready" group="panda_arm"> + <joint name="panda_joint1" value="0" /> + <joint name="panda_joint2" value="-0.2128" /> + <joint name="panda_joint3" value="0" /> + <joint name="panda_joint4" value="-1.928" /> + <joint name="panda_joint5" value="0" /> + <joint name="panda_joint6" value="1.7741" /> + <joint name="panda_joint7" value="0" /> + </group_state> + <group_state name="home" group="panda_arm_hand"> + <joint name="panda_joint1" value="0" /> + <joint name="panda_joint2" value="0" /> + <joint name="panda_joint3" value="0" /> + <joint name="panda_joint4" value="0" /> + <joint name="panda_joint5" value="0" /> + <joint name="panda_joint6" value="0" /> + <joint name="panda_joint7" value="0.7918" /> + </group_state> + <group_state name="ready" group="panda_arm_hand"> + <joint name="panda_joint1" value="0" /> + <joint name="panda_joint2" value="-0.3912" /> + <joint name="panda_joint3" value="0" /> + <joint name="panda_joint4" value="-1.9161" /> + <joint name="panda_joint5" value="0" /> + <joint name="panda_joint6" value="1.5029" /> + <joint name="panda_joint7" value="0.7918" /> + </group_state> + <!--END EFFECTOR: Purpose: Represent information about an end effector.--> + <end_effector name="hand" parent_link="panda_hand" group="hand" parent_group="panda_arm_hand" /> + <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. --> + <disable_collisions link1="panda_hand" link2="panda_leftfinger" reason="Adjacent" /> + <disable_collisions link1="panda_hand" link2="panda_link3" reason="Never" /> + <disable_collisions link1="panda_hand" link2="panda_link4" reason="Never" /> + <disable_collisions link1="panda_hand" link2="panda_link5" reason="Default" /> + <disable_collisions link1="panda_hand" link2="panda_link6" reason="Never" /> + <disable_collisions link1="panda_hand" link2="panda_link7" reason="Adjacent" /> + <disable_collisions link1="panda_hand" link2="panda_rightfinger" reason="Adjacent" /> + <disable_collisions link1="panda_leftfinger" link2="panda_link3" reason="Never" /> + <disable_collisions link1="panda_leftfinger" link2="panda_link4" reason="Never" /> + <disable_collisions link1="panda_leftfinger" link2="panda_link6" reason="Never" /> + <disable_collisions link1="panda_leftfinger" link2="panda_link7" reason="Never" /> + <disable_collisions link1="panda_leftfinger" link2="panda_rightfinger" reason="Default" /> + <disable_collisions link1="panda_link0" link2="panda_link1" reason="Adjacent" /> + <disable_collisions link1="panda_link0" link2="panda_link2" reason="Never" /> + <disable_collisions link1="panda_link0" link2="panda_link3" reason="Never" /> + <disable_collisions link1="panda_link0" link2="panda_link4" reason="Never" /> + <disable_collisions link1="panda_link1" link2="panda_link2" reason="Adjacent" /> + <disable_collisions link1="panda_link1" link2="panda_link3" reason="Never" /> + <disable_collisions link1="panda_link1" link2="panda_link4" reason="Never" /> + <disable_collisions link1="panda_link2" link2="panda_link3" reason="Adjacent" /> + <disable_collisions link1="panda_link2" link2="panda_link4" reason="Never" /> + <disable_collisions link1="panda_link2" link2="panda_link6" reason="Never" /> + <disable_collisions link1="panda_link3" link2="panda_link4" reason="Adjacent" /> + <disable_collisions link1="panda_link3" link2="panda_link5" reason="Never" /> + <disable_collisions link1="panda_link3" link2="panda_link6" reason="Never" /> + <disable_collisions link1="panda_link3" link2="panda_link7" reason="Never" /> + <disable_collisions link1="panda_link3" link2="panda_rightfinger" reason="Never" /> + <disable_collisions link1="panda_link4" link2="panda_link5" reason="Adjacent" /> + <disable_collisions link1="panda_link4" link2="panda_link6" reason="Never" /> + <disable_collisions link1="panda_link4" link2="panda_link7" reason="Never" /> + <disable_collisions link1="panda_link4" link2="panda_rightfinger" reason="Never" /> + <disable_collisions link1="panda_link5" link2="panda_link6" reason="Adjacent" /> + <disable_collisions link1="panda_link5" link2="panda_link7" reason="Default" /> + <disable_collisions link1="panda_link6" link2="panda_link7" reason="Adjacent" /> + <disable_collisions link1="panda_link6" link2="panda_rightfinger" reason="Never" /> + <disable_collisions link1="panda_link7" link2="panda_rightfinger" reason="Never" /> +</robot> diff --git a/franka_moveit_config/launch/default_warehouse_db.launch b/panda_moveit_config/launch/default_warehouse_db.launch similarity index 73% rename from franka_moveit_config/launch/default_warehouse_db.launch rename to panda_moveit_config/launch/default_warehouse_db.launch index db6572f..6901960 100644 --- a/franka_moveit_config/launch/default_warehouse_db.launch +++ b/panda_moveit_config/launch/default_warehouse_db.launch @@ -2,10 +2,10 @@ <arg name="reset" default="false"/> <!-- If not specified, we'll use a default database location --> - <arg name="moveit_warehouse_database_path" default="$(find franka_moveit_config)/default_warehouse_mongo_db" /> + <arg name="moveit_warehouse_database_path" default="$(find panda_moveit_config)/default_warehouse_mongo_db" /> <!-- Launch the warehouse with the configured database location --> - <include file="$(find franka_moveit_config)/launch/warehouse.launch"> + <include file="$(find panda_moveit_config)/launch/warehouse.launch"> <arg name="moveit_warehouse_database_path" value="$(arg moveit_warehouse_database_path)" /> </include> diff --git a/franka_moveit_config/launch/demo.launch b/panda_moveit_config/launch/demo.launch similarity index 83% rename from franka_moveit_config/launch/demo.launch rename to panda_moveit_config/launch/demo.launch index 6b7de59..1faff8e 100644 --- a/franka_moveit_config/launch/demo.launch +++ b/panda_moveit_config/launch/demo.launch @@ -3,7 +3,7 @@ <!-- By default, we do not start a database (it can be large) --> <arg name="db" default="false" /> <!-- Allow user to specify database location --> - <arg name="db_path" default="$(find franka_moveit_config)/default_warehouse_mongo_db" /> + <arg name="db_path" default="$(find panda_moveit_config)/default_warehouse_mongo_db" /> <!-- By default, we are not in debug mode --> <arg name="debug" default="false" /> @@ -19,7 +19,7 @@ <arg name="use_gui" default="false" /> <!-- Load the URDF, SRDF and other .yaml configuration files on the param server --> - <include file="$(find franka_moveit_config)/launch/planning_context.launch"> + <include file="$(find panda_moveit_config)/launch/planning_context.launch"> <arg name="load_robot_description" value="true"/> </include> @@ -36,7 +36,7 @@ <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" /> <!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) --> - <include file="$(find franka_moveit_config)/launch/move_group.launch"> + <include file="$(find panda_moveit_config)/launch/move_group.launch"> <arg name="allow_trajectory_execution" value="true"/> <arg name="fake_execution" value="true"/> <arg name="info" value="true"/> @@ -44,13 +44,13 @@ </include> <!-- Run Rviz and load the default config to see the state of the move_group node --> - <include file="$(find franka_moveit_config)/launch/moveit_rviz.launch"> + <include file="$(find panda_moveit_config)/launch/moveit_rviz.launch"> <arg name="config" value="true"/> <arg name="debug" value="$(arg debug)"/> </include> <!-- If database loading was enabled, start mongodb as well --> - <include file="$(find franka_moveit_config)/launch/default_warehouse_db.launch" if="$(arg db)"> + <include file="$(find panda_moveit_config)/launch/default_warehouse_db.launch" if="$(arg db)"> <arg name="moveit_warehouse_database_path" value="$(arg db_path)"/> </include> diff --git a/franka_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/panda_moveit_config/launch/fake_moveit_controller_manager.launch.xml similarity index 78% rename from franka_moveit_config/launch/fake_moveit_controller_manager.launch.xml rename to panda_moveit_config/launch/fake_moveit_controller_manager.launch.xml index 9f3148a..c95563d 100644 --- a/franka_moveit_config/launch/fake_moveit_controller_manager.launch.xml +++ b/panda_moveit_config/launch/fake_moveit_controller_manager.launch.xml @@ -4,6 +4,6 @@ <param name="moveit_controller_manager" value="moveit_fake_controller_manager/MoveItFakeControllerManager"/> <!-- The rest of the params are specific to this plugin --> - <rosparam file="$(find franka_moveit_config)/config/fake_controllers.yaml"/> + <rosparam file="$(find panda_moveit_config)/config/fake_controllers.yaml"/> </launch> diff --git a/franka_moveit_config/launch/joystick_control.launch b/panda_moveit_config/launch/joystick_control.launch similarity index 100% rename from franka_moveit_config/launch/joystick_control.launch rename to panda_moveit_config/launch/joystick_control.launch diff --git a/franka_moveit_config/launch/move_group.launch b/panda_moveit_config/launch/move_group.launch similarity index 79% rename from franka_moveit_config/launch/move_group.launch rename to panda_moveit_config/launch/move_group.launch index c7e0a7b..5b8c866 100644 --- a/franka_moveit_config/launch/move_group.launch +++ b/panda_moveit_config/launch/move_group.launch @@ -1,11 +1,11 @@ <launch> - <include file="$(find franka_moveit_config)/launch/planning_context.launch" /> + <include file="$(find panda_moveit_config)/launch/planning_context.launch" /> <!-- GDB Debug Option --> <arg name="debug" default="false" /> <arg unless="$(arg debug)" name="launch_prefix" value="" /> - <arg if="$(arg debug)" name="launch_prefix" value="gdb -x $(find franka_moveit_config)/launch/gdb_settings.gdb --ex run --args" /> + <arg if="$(arg debug)" name="launch_prefix" value="gdb -x $(find panda_moveit_config)/launch/gdb_settings.gdb --ex run --args" /> <!-- Verbose Mode Option --> <arg name="info" default="$(arg debug)" /> @@ -20,20 +20,20 @@ <arg name="publish_monitored_planning_scene" default="true"/> <!-- Planning Functionality --> - <include ns="move_group" file="$(find franka_moveit_config)/launch/planning_pipeline.launch.xml"> + <include ns="move_group" file="$(find panda_moveit_config)/launch/planning_pipeline.launch.xml"> <arg name="pipeline" value="ompl" /> </include> <!-- Trajectory Execution Functionality --> - <include ns="move_group" file="$(find franka_moveit_config)/launch/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)"> + <include ns="move_group" file="$(find panda_moveit_config)/launch/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)"> <arg name="moveit_manage_controllers" value="true" /> - <arg name="moveit_controller_manager" value="franka_emika" unless="$(arg fake_execution)"/> + <arg name="moveit_controller_manager" value="panda" unless="$(arg fake_execution)"/> <arg name="moveit_controller_manager" value="fake" if="$(arg fake_execution)"/> </include> <!-- Sensors Functionality --> - <include ns="move_group" file="$(find franka_moveit_config)/launch/sensor_manager.launch.xml" if="$(arg allow_trajectory_execution)"> - <arg name="moveit_sensor_manager" value="franka_emika" /> + <include ns="move_group" file="$(find panda_moveit_config)/launch/sensor_manager.launch.xml" if="$(arg allow_trajectory_execution)"> + <arg name="moveit_sensor_manager" value="panda" /> </include> <!-- Start the actual move_group node/action server --> diff --git a/franka_moveit_config/launch/move_to_start.launch b/panda_moveit_config/launch/move_to_start.launch similarity index 50% rename from franka_moveit_config/launch/move_to_start.launch rename to panda_moveit_config/launch/move_to_start.launch index 54c7ada..a6a966e 100644 --- a/franka_moveit_config/launch/move_to_start.launch +++ b/panda_moveit_config/launch/move_to_start.launch @@ -1,16 +1,16 @@ <?xml version="1.0" ?> <launch> <arg name="robot_ip" default="robot.franka.de" /> - <arg name="arm_id" default="franka_emika" /> + <arg name="arm_id" default="panda" /> - <include file="$(find franka_hw)/launch/franka_hw.launch"> + <include file="$(find franka_control)/launch/franka_control.launch"> <arg name="robot_ip" value="$(arg robot_ip)" /> <arg name="arm_id" value="$(arg arm_id)" /> </include> - <include file="$(find franka_moveit_config)/launch/franka_moveit.launch"> + <include file="$(find panda_moveit_config)/launch/panda_moveit.launch"> <arg name="arm_id" value="$(arg arm_id)" /> </include> <group ns="$(arg arm_id)"> - <node name="move_to_start" pkg="franka_moveit_config" type="move_to_start.py" output="screen" required="true" /> + <node name="move_to_start" pkg="panda_moveit_config" type="move_to_start.py" output="screen" required="true" /> </group> </launch> diff --git a/franka_moveit_config/launch/moveit.rviz b/panda_moveit_config/launch/moveit.rviz similarity index 89% rename from franka_moveit_config/launch/moveit.rviz rename to panda_moveit_config/launch/moveit.rviz index 5e2fc05..da6da92 100644 --- a/franka_moveit_config/launch/moveit.rviz +++ b/panda_moveit_config/launch/moveit.rviz @@ -66,61 +66,61 @@ Visualization Manager: Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order - franka_emika_hand: + panda_hand: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_leftfinger: + panda_leftfinger: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link0: + panda_link0: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link1: + panda_link1: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link2: + panda_link2: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link3: + panda_link3: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link4: + panda_link4: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link5: + panda_link5: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link6: + panda_link6: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link7: + panda_link7: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link8: + panda_link8: Alpha: 1 Show Axes: false Show Trail: false - franka_emika_rightfinger: + panda_rightfinger: Alpha: 1 Show Axes: false Show Trail: false @@ -147,14 +147,14 @@ Visualization Manager: Goal State Color: 250; 128; 0 Interactive Marker Size: 0 Joint Violation Color: 255; 0; 255 - Planning Group: franka_with_gripper + Planning Group: panda_arm_hand Query Goal State: true Query Start State: false Show Workspace: false Start State Alpha: 1 Start State Color: 0; 255; 0 Planning Scene Topic: move_group/monitored_planning_scene - Robot Description: franka_emika/robot_description + Robot Description: robot_description Scene Geometry: Scene Alpha: 1 Scene Color: 50; 230; 50 @@ -170,61 +170,61 @@ Visualization Manager: Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order - franka_emika_hand: + panda_hand: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_leftfinger: + panda_leftfinger: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link0: + panda_link0: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link1: + panda_link1: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link2: + panda_link2: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link3: + panda_link3: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link4: + panda_link4: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link5: + panda_link5: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link6: + panda_link6: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link7: + panda_link7: Alpha: 1 Show Axes: false Show Trail: false Value: true - franka_emika_link8: + panda_link8: Alpha: 1 Show Axes: false Show Trail: false - franka_emika_rightfinger: + panda_rightfinger: Alpha: 1 Show Axes: false Show Trail: false @@ -236,7 +236,7 @@ Visualization Manager: Enabled: true Global Options: Background Color: 48; 48; 48 - Fixed Frame: franka_emika_link0 + Fixed Frame: panda_link0 Frame Rate: 30 Name: root Tools: @@ -263,7 +263,7 @@ Visualization Manager: Name: Current View Near Clip Distance: 0.00999999978 Pitch: 0.104796879 - Target Frame: franka_emika_link0 + Target Frame: panda_link0 Value: XYOrbit (rviz) Yaw: 5.9349494 Saved: ~ diff --git a/franka_moveit_config/launch/moveit_rviz.launch b/panda_moveit_config/launch/moveit_rviz.launch similarity index 75% rename from franka_moveit_config/launch/moveit_rviz.launch rename to panda_moveit_config/launch/moveit_rviz.launch index d7291cd..71f196e 100644 --- a/franka_moveit_config/launch/moveit_rviz.launch +++ b/panda_moveit_config/launch/moveit_rviz.launch @@ -6,14 +6,14 @@ <arg name="config" default="true" /> <arg unless="$(arg config)" name="command_args" value="" /> - <arg if="$(arg config)" name="command_args" value="-d $(find franka_moveit_config)/launch/moveit.rviz" /> + <arg if="$(arg config)" name="command_args" value="-d $(find panda_moveit_config)/launch/moveit.rviz" /> - <arg name="arm_id" default="franka_emika" /> + <arg name="arm_id" default="panda" /> <group ns="$(arg arm_id)"> <node name="$(anon rviz)" launch-prefix="$(arg launch_prefix)" pkg="rviz" type="rviz" respawn="false" args="$(arg command_args)" output="screen"> - <rosparam command="load" file="$(find franka_moveit_config)/config/kinematics.yaml"/> + <rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/> </node> </group> diff --git a/franka_moveit_config/launch/ompl_planning_pipeline.launch.xml b/panda_moveit_config/launch/ompl_planning_pipeline.launch.xml similarity index 91% rename from franka_moveit_config/launch/ompl_planning_pipeline.launch.xml rename to panda_moveit_config/launch/ompl_planning_pipeline.launch.xml index 211506b..b2918d9 100644 --- a/franka_moveit_config/launch/ompl_planning_pipeline.launch.xml +++ b/panda_moveit_config/launch/ompl_planning_pipeline.launch.xml @@ -17,6 +17,6 @@ <param name="request_adapters" value="$(arg planning_adapters)" /> <param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" /> - <rosparam command="load" file="$(find franka_moveit_config)/config/ompl_planning.yaml"/> + <rosparam command="load" file="$(find panda_moveit_config)/config/ompl_planning.yaml"/> </launch> diff --git a/franka_moveit_config/launch/franka_moveit.launch b/panda_moveit_config/launch/panda_moveit.launch similarity index 74% rename from franka_moveit_config/launch/franka_moveit.launch rename to panda_moveit_config/launch/panda_moveit.launch index 58cf112..4af35f9 100644 --- a/franka_moveit_config/launch/franka_moveit.launch +++ b/panda_moveit_config/launch/panda_moveit.launch @@ -1,11 +1,11 @@ <?xml version="1.0" ?> <launch> - <arg name="arm_id" default="franka_emika" /> + <arg name="arm_id" default="panda" /> <!-- Valid values: "position", "effort" --> <arg name="controller" default="position" /> <group ns="$(arg arm_id)"> <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="$(arg controller)_joint_trajectory_controller --shutdown-timeout 2"/> - <include file="$(find franka_moveit_config)/launch/move_group.launch" /> + <include file="$(find panda_moveit_config)/launch/move_group.launch" /> </group> </launch> diff --git a/franka_moveit_config/launch/franka_emika_moveit_controller_manager.launch.xml b/panda_moveit_config/launch/panda_moveit_controller_manager.launch.xml similarity index 100% rename from franka_moveit_config/launch/franka_emika_moveit_controller_manager.launch.xml rename to panda_moveit_config/launch/panda_moveit_controller_manager.launch.xml diff --git a/franka_moveit_config/launch/franka_emika_moveit_sensor_manager.launch.xml b/panda_moveit_config/launch/panda_moveit_sensor_manager.launch.xml similarity index 100% rename from franka_moveit_config/launch/franka_emika_moveit_sensor_manager.launch.xml rename to panda_moveit_config/launch/panda_moveit_sensor_manager.launch.xml diff --git a/franka_moveit_config/launch/planning_context.launch b/panda_moveit_config/launch/planning_context.launch similarity index 76% rename from franka_moveit_config/launch/planning_context.launch rename to panda_moveit_config/launch/planning_context.launch index 6f0455a..1d4b6e0 100644 --- a/franka_moveit_config/launch/planning_context.launch +++ b/panda_moveit_config/launch/planning_context.launch @@ -6,19 +6,19 @@ <arg name="robot_description" default="robot_description"/> <!-- Load universal robot description format (URDF) --> - <param if="$(arg load_robot_description)" name="$(arg robot_description)" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/FEA_01_01_Gripper.urdf.xacro'"/> + <param if="$(arg load_robot_description)" name="$(arg robot_description)" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'"/> <!-- The semantic description that corresponds to the URDF --> - <param name="$(arg robot_description)_semantic" textfile="$(find franka_moveit_config)/config/franka_emika.srdf" /> + <param name="$(arg robot_description)_semantic" textfile="$(find panda_moveit_config)/config/panda_arm_hand.srdf" /> <!-- Load updated joint limits (override information from URDF) --> <group ns="$(arg robot_description)_planning"> - <rosparam command="load" file="$(find franka_moveit_config)/config/joint_limits.yaml"/> + <rosparam command="load" file="$(find panda_moveit_config)/config/joint_limits.yaml"/> </group> <!-- Load default settings for kinematics; these settings are overridden by settings in a node's namespace --> <group ns="$(arg robot_description)_kinematics"> - <rosparam command="load" file="$(find franka_moveit_config)/config/kinematics.yaml"/> + <rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/> </group> </launch> diff --git a/franka_moveit_config/launch/planning_pipeline.launch.xml b/panda_moveit_config/launch/planning_pipeline.launch.xml similarity index 69% rename from franka_moveit_config/launch/planning_pipeline.launch.xml rename to panda_moveit_config/launch/planning_pipeline.launch.xml index 69fd5f3..ac6838d 100644 --- a/franka_moveit_config/launch/planning_pipeline.launch.xml +++ b/panda_moveit_config/launch/planning_pipeline.launch.xml @@ -5,6 +5,6 @@ <arg name="pipeline" default="ompl" /> - <include file="$(find franka_moveit_config)/launch/$(arg pipeline)_planning_pipeline.launch.xml" /> + <include file="$(find panda_moveit_config)/launch/$(arg pipeline)_planning_pipeline.launch.xml" /> </launch> diff --git a/franka_moveit_config/launch/run_benchmark_ompl.launch b/panda_moveit_config/launch/run_benchmark_ompl.launch similarity index 63% rename from franka_moveit_config/launch/run_benchmark_ompl.launch rename to panda_moveit_config/launch/run_benchmark_ompl.launch index ae1e816..6bf8ba2 100644 --- a/franka_moveit_config/launch/run_benchmark_ompl.launch +++ b/panda_moveit_config/launch/run_benchmark_ompl.launch @@ -4,19 +4,19 @@ <arg name="cfg" /> <!-- Load URDF --> - <include file="$(find franka_moveit_config)/launch/planning_context.launch"> + <include file="$(find panda_moveit_config)/launch/planning_context.launch"> <arg name="load_robot_description" value="true"/> </include> <!-- Start the database --> - <include file="$(find franka_moveit_config)/launch/warehouse.launch"> + <include file="$(find panda_moveit_config)/launch/warehouse.launch"> <arg name="moveit_warehouse_database_path" value="moveit_ompl_benchmark_warehouse"/> </include> <!-- Start Benchmark Executable --> <node name="$(anon moveit_benchmark)" pkg="moveit_ros_benchmarks" type="moveit_run_benchmark" args="$(arg cfg) --benchmark-planners" respawn="false" output="screen"> - <rosparam command="load" file="$(find franka_moveit_config)/config/kinematics.yaml"/> - <rosparam command="load" file="$(find franka_moveit_config)/config/ompl_planning.yaml"/> + <rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/> + <rosparam command="load" file="$(find panda_moveit_config)/config/ompl_planning.yaml"/> </node> </launch> diff --git a/franka_moveit_config/launch/sensor_manager.launch.xml b/panda_moveit_config/launch/sensor_manager.launch.xml similarity index 72% rename from franka_moveit_config/launch/sensor_manager.launch.xml rename to panda_moveit_config/launch/sensor_manager.launch.xml index 197fffa..c74d05c 100644 --- a/franka_moveit_config/launch/sensor_manager.launch.xml +++ b/panda_moveit_config/launch/sensor_manager.launch.xml @@ -8,7 +8,7 @@ <param name="max_range" type="double" value="5.0" /> <!-- Load the robot specific sensor manager; this sets the moveit_sensor_manager ROS parameter --> - <arg name="moveit_sensor_manager" default="franka_emika" /> - <include file="$(find franka_moveit_config)/launch/$(arg moveit_sensor_manager)_moveit_sensor_manager.launch.xml" /> + <arg name="moveit_sensor_manager" default="panda" /> + <include file="$(find panda_moveit_config)/launch/$(arg moveit_sensor_manager)_moveit_sensor_manager.launch.xml" /> </launch> diff --git a/franka_moveit_config/launch/setup_assistant.launch b/panda_moveit_config/launch/setup_assistant.launch similarity index 75% rename from franka_moveit_config/launch/setup_assistant.launch rename to panda_moveit_config/launch/setup_assistant.launch index 0bff427..28e4e8b 100644 --- a/franka_moveit_config/launch/setup_assistant.launch +++ b/panda_moveit_config/launch/setup_assistant.launch @@ -7,6 +7,6 @@ <arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" /> <!-- Run --> - <node pkg="moveit_setup_assistant" type="moveit_setup_assistant" name="moveit_setup_assistant" args="--config_pkg=franka_moveit_config" launch-prefix="$(arg launch_prefix)" output="screen" /> + <node pkg="moveit_setup_assistant" type="moveit_setup_assistant" name="moveit_setup_assistant" args="--config_pkg=panda_moveit_config" launch-prefix="$(arg launch_prefix)" output="screen" /> </launch> diff --git a/franka_moveit_config/launch/trajectory_execution.launch.xml b/panda_moveit_config/launch/trajectory_execution.launch.xml similarity index 85% rename from franka_moveit_config/launch/trajectory_execution.launch.xml rename to panda_moveit_config/launch/trajectory_execution.launch.xml index 6c53f13..b6c03c9 100644 --- a/franka_moveit_config/launch/trajectory_execution.launch.xml +++ b/panda_moveit_config/launch/trajectory_execution.launch.xml @@ -14,7 +14,7 @@ <param name="trajectory_execution/allowed_start_tolerance" value="0.01"/> <!-- default 0.01 --> <!-- Load the robot specific controller manager; this sets the moveit_controller_manager ROS parameter --> - <arg name="moveit_controller_manager" default="franka_emika" /> - <include file="$(find franka_moveit_config)/launch/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml" /> + <arg name="moveit_controller_manager" default="panda" /> + <include file="$(find panda_moveit_config)/launch/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml" /> </launch> diff --git a/franka_moveit_config/launch/warehouse.launch b/panda_moveit_config/launch/warehouse.launch similarity index 83% rename from franka_moveit_config/launch/warehouse.launch rename to panda_moveit_config/launch/warehouse.launch index 3c2b0c6..6889b8e 100644 --- a/franka_moveit_config/launch/warehouse.launch +++ b/panda_moveit_config/launch/warehouse.launch @@ -4,7 +4,7 @@ <arg name="moveit_warehouse_database_path" /> <!-- Load warehouse parameters --> - <include file="$(find franka_moveit_config)/launch/warehouse_settings.launch.xml" /> + <include file="$(find panda_moveit_config)/launch/warehouse_settings.launch.xml" /> <!-- Run the DB server --> <node name="$(anon mongo_wrapper_ros)" cwd="ROS_HOME" type="mongo_wrapper_ros.py" pkg="warehouse_ros_mongo"> diff --git a/franka_moveit_config/launch/warehouse_settings.launch.xml b/panda_moveit_config/launch/warehouse_settings.launch.xml similarity index 100% rename from franka_moveit_config/launch/warehouse_settings.launch.xml rename to panda_moveit_config/launch/warehouse_settings.launch.xml diff --git a/franka_moveit_config/mainpage.dox b/panda_moveit_config/mainpage.dox similarity index 100% rename from franka_moveit_config/mainpage.dox rename to panda_moveit_config/mainpage.dox diff --git a/franka_moveit_config/package.xml b/panda_moveit_config/package.xml similarity index 82% rename from franka_moveit_config/package.xml rename to panda_moveit_config/package.xml index 299d891..0d07bf3 100644 --- a/franka_moveit_config/package.xml +++ b/panda_moveit_config/package.xml @@ -1,12 +1,12 @@ <?xml version="1.0"?> <package format="2"> - <name>franka_moveit_config</name> + <name>panda_moveit_config</name> <version>0.0.1</version> - <description> A partly automatically generated package with all the configuration and launch files for using FRANKA EMIKA with MoveIt!</description> - <maintainer email="info@franka.de">FRANKA EMIKA Research Interface Team</maintainer> + <description> A partly automatically generated package with all the configuration and launch files for using Panda research with MoveIt!</description> + <maintainer email="info@franka.de">FRANKA EMIKA Research Interface Team</maintainer> <license>NONE</license> - - <url type="website">http://wiki.ros.org/franka_moveit_config</url> + + <url type="website">http://wiki.ros.org/panda_moveit_config</url> <url type="repository">https://github.com/frankaemika/franka_ros</url> <url type="bugtracker">https://github.com/frankaemika/franka_ros/issues</url> <author>FRANKA EMIKA Research Interface Team</author> @@ -14,7 +14,7 @@ <buildtool_depend>catkin</buildtool_depend> <depend>franka_description</depend> - + <exec_depend>joint_state_publisher</exec_depend> <exec_depend>joint_trajectory_controller</exec_depend> <exec_depend>moveit_commander</exec_depend> diff --git a/franka_moveit_config/rosdoc.yaml b/panda_moveit_config/rosdoc.yaml similarity index 100% rename from franka_moveit_config/rosdoc.yaml rename to panda_moveit_config/rosdoc.yaml diff --git a/franka_moveit_config/scripts/move_to_start.py b/panda_moveit_config/scripts/move_to_start.py similarity index 86% rename from franka_moveit_config/scripts/move_to_start.py rename to panda_moveit_config/scripts/move_to_start.py index 7ab4a50..f6d5221 100755 --- a/franka_moveit_config/scripts/move_to_start.py +++ b/panda_moveit_config/scripts/move_to_start.py @@ -7,6 +7,6 @@ from actionlib_msgs.msg import GoalStatusArray if __name__ == '__main__': rospy.init_node('move_to_start') rospy.wait_for_message('move_group/status', GoalStatusArray) - commander = MoveGroupCommander('franka') + commander = MoveGroupCommander('panda_arm') commander.set_named_target('ready') commander.go() -- GitLab