Skip to content
Snippets Groups Projects
Commit e06ba267 authored by Florian Walch's avatar Florian Walch
Browse files

Merge pull request #76 in SWDEV/franka_ros from move-to-start-example to develop

* commit 'ecc13f8f':
  Move move_to_start.py to franka_example_controllers
parents 55242e6a ecc13f8f
No related branches found
No related tags found
No related merge requests found
......@@ -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
......
......@@ -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}
)
......
......@@ -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>
......@@ -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>
......
......@@ -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;
}
......
......@@ -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;
}
}
......
......@@ -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;
}
......
......@@ -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;
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment