diff --git a/CHANGELOG.md b/CHANGELOG.md index ebfa573dff662fc926f6efa431f70f4172a36d55..b52aa501c9ec33ad7373fbbcf5cef6355d5db2f1 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -11,6 +11,7 @@ Requires `libfranka` >= 0.3.0 * Fixed linker errors when building with `-DFranka_DIR` while an older version of `ros-kinetic-libfranka` is installed * Added gripper joint state publisher to `franka_visualization` + * Moved `move_to_start.py` example script to `franka_example_controllers` ## 0.2.2 - 2018-01-31 diff --git a/franka_example_controllers/CMakeLists.txt b/franka_example_controllers/CMakeLists.txt index 235c5cb69c4e2dcda02213c0be2e6bd3aa7b21bc..bce35bb1db1c6008d5598078f3ff2e41d2147e5c 100644 --- a/franka_example_controllers/CMakeLists.txt +++ b/franka_example_controllers/CMakeLists.txt @@ -97,7 +97,7 @@ install(FILES franka_example_controllers_plugin.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) catkin_install_python( - PROGRAMS scripts/interactive_marker.py + PROGRAMS scripts/interactive_marker.py scripts/move_to_start.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) diff --git a/panda_moveit_config/launch/move_to_start.launch b/franka_example_controllers/launch/move_to_start.launch similarity index 82% rename from panda_moveit_config/launch/move_to_start.launch rename to franka_example_controllers/launch/move_to_start.launch index 1082569da60be871fc09c098b96f03410f57f44d..ed8accb2b7fd8bc9d4e7636b08fc210e5c2f7601 100644 --- a/panda_moveit_config/launch/move_to_start.launch +++ b/franka_example_controllers/launch/move_to_start.launch @@ -13,6 +13,6 @@ <arg name="arm_id" value="$(arg arm_id)" /> </include> <group ns="$(arg arm_id)"> - <node name="move_to_start" pkg="panda_moveit_config" type="move_to_start.py" output="screen" required="true" /> + <node name="move_to_start" pkg="franka_example_controllers" type="move_to_start.py" output="screen" required="true" /> </group> </launch> diff --git a/franka_example_controllers/package.xml b/franka_example_controllers/package.xml index 22b271e048cb0cfd1e3fe576615090a64555faef..ea2fb5a7731f168d6625b6d99e4c1ea0dc3e0f7e 100644 --- a/franka_example_controllers/package.xml +++ b/franka_example_controllers/package.xml @@ -31,6 +31,7 @@ <exec_depend>franka_control</exec_depend> <exec_depend>franka_description</exec_depend> <exec_depend>message_runtime</exec_depend> + <exec_depend>panda_moveit_config</exec_depend> <exec_depend>rospy</exec_depend> <export> diff --git a/panda_moveit_config/scripts/move_to_start.py b/franka_example_controllers/scripts/move_to_start.py similarity index 100% rename from panda_moveit_config/scripts/move_to_start.py rename to franka_example_controllers/scripts/move_to_start.py diff --git a/franka_example_controllers/src/cartesian_pose_example_controller.cpp b/franka_example_controllers/src/cartesian_pose_example_controller.cpp index 223de376e235574bb01d7a542f7ae7edc2e8bfc7..4389fa0721909b1656eac1962cbd30b0aca9a5b1 100644 --- a/franka_example_controllers/src/cartesian_pose_example_controller.cpp +++ b/franka_example_controllers/src/cartesian_pose_example_controller.cpp @@ -54,7 +54,7 @@ bool CartesianPoseExampleController::init(hardware_interface::RobotHW* robot_har if (std::abs(state_handle.getRobotState().q_d[i] - q_start[i]) > 0.1) { ROS_ERROR_STREAM( "CartesianPoseExampleController: Robot is not in the expected starting position for " - "running this example. Run `roslaunch panda_moveit_config move_to_start.launch " + "running this example. Run `roslaunch franka_example_controllers move_to_start.launch " "robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first."); return false; } diff --git a/franka_example_controllers/src/cartesian_velocity_example_controller.cpp b/franka_example_controllers/src/cartesian_velocity_example_controller.cpp index 7ce5b69d9f14919ec9a8110271266b2cd8b644e0..ad7b64bd87f9d24f5f736f8791c5aa390ac17c94 100644 --- a/franka_example_controllers/src/cartesian_velocity_example_controller.cpp +++ b/franka_example_controllers/src/cartesian_velocity_example_controller.cpp @@ -54,8 +54,9 @@ bool CartesianVelocityExampleController::init(hardware_interface::RobotHW* robot if (std::abs(state_handle.getRobotState().q_d[i] - q_start[i]) > 0.1) { ROS_ERROR_STREAM( "CartesianVelocityExampleController: Robot is not in the expected starting position " - "for running this example. Run `roslaunch panda_moveit_config move_to_start.launch " - "robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first."); + "for running this example. Run `roslaunch franka_example_controllers " + "move_to_start.launch robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` " + "first."); return false; } } diff --git a/franka_example_controllers/src/joint_position_example_controller.cpp b/franka_example_controllers/src/joint_position_example_controller.cpp index 847da23de598711bbc607d68531e23a7d5b35a75..b630014a099080be6107eb61861f1e18ca2cc9da 100644 --- a/franka_example_controllers/src/joint_position_example_controller.cpp +++ b/franka_example_controllers/src/joint_position_example_controller.cpp @@ -46,7 +46,7 @@ bool JointPositionExampleController::init(hardware_interface::RobotHW* robot_har if (std::abs(position_joint_handles_[i].getPosition() - q_start[i]) > 0.1) { ROS_ERROR_STREAM( "JointPositionExampleController: Robot is not in the expected starting position for " - "running this example. Run `roslaunch panda_moveit_config move_to_start.launch " + "running this example. Run `roslaunch franka_example_controllers move_to_start.launch " "robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first."); return false; } diff --git a/franka_example_controllers/src/joint_velocity_example_controller.cpp b/franka_example_controllers/src/joint_velocity_example_controller.cpp index bcc3ca286d79373e6a74bcd393b1f7f331b7049a..dbe4c235b2d75618b1c33f67fc7e30ca1d9b42f9 100644 --- a/franka_example_controllers/src/joint_velocity_example_controller.cpp +++ b/franka_example_controllers/src/joint_velocity_example_controller.cpp @@ -61,7 +61,7 @@ bool JointVelocityExampleController::init(hardware_interface::RobotHW* robot_har if (std::abs(state_handle.getRobotState().q_d[i] - q_start[i]) > 0.1) { ROS_ERROR_STREAM( "JointVelocityExampleController: Robot is not in the expected starting position for " - "running this example. Run `roslaunch panda_moveit_config move_to_start.launch " + "running this example. Run `roslaunch franka_example_controllers move_to_start.launch " "robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first."); return false; }