Skip to content
Snippets Groups Projects
Commit ab47d806 authored by Johannes Mey's avatar Johannes Mey
Browse files

reduce repo to just franka_description

parent 0f83665d
No related branches found
No related tags found
No related merge requests found
Showing
with 0 additions and 1449 deletions
# CHANGELOG
## 0.7.0 - UNRELEASED
Requires `libfranka` >= 0.7.0
* **BREAKING** moved services and action from `franka_control` to `franka_msgs`.
* **BREAKING** moved Service container from `franka_control` to `franka_hw`.
* `franka_example_controllers` : Added example for dual-arm control based on franka_combinable_hw.
* `franka_description` :
- Added an example urdf with two panda arms.
- **BREAKING** Updated collision volumes.
- Removed invalid `axis` for `joint8`.
* `franka_hw`:
- Added hardware classes to support torque-controlling multiple robots from one controller.
- Refactored FrankaHW class to serve as base class (e.g. for FrankaCombinableHW).
- Added joint limits checking to FrankaHW which means parameterized warning prints when approaching limits.
- Made initial collision behavior a parameter.
- Added default constructor and init method to FrankaHW.
- **BREAKING** moved parsing of parameters from control node to FrankaHW::init.
- **BREAKING** made libfranka robot a member of FrankaHW.
- Added missing return value to `franka::ControllerMode` stream operator function.
* `franka_control`:
- Added control node that can runs a `FrankaCombinedHW` to control mulitple Pandas.
- Publish whole `libfranka` `franka::RobotState` in `franka_state_controller`.
* `franka_example_controllers`:
- Cartesian impedance example controller: Interpolate desired orientations with slerp and change orientation error
to quaternion.
* **BREAKING** Moved `panda_moveit_config` to [`ros-planning`](https://github.com/ros-planning/panda_moveit_config).
* Added support for ROS Melodic Morenia.
* Raised minimum CMake version to 3.4 to match `libfranka`.
* Add rosparam to choose value of `franka::RealtimeConfig`.
* Fix unused parameter bugs in `FrankaModelHandle` (#78).
## 0.6.0 - 2018-08-08
Requires `libfranka` >= 0.5.0
* **BREAKING** Fixes for MoveIt, improving robot performance:
* Fixed joint velocity and acceleration limits in `joint_limits.yaml`
* Use desired joint state for move group
* **BREAKING** Updated joint limits in URDF
* **BREAKING** Fixed velocity, acceleration and jerk limits in `franka_hw`
* **BREAKING** Start `franka_gripper_node` when giving `load_gripper:=true` to `franka_control.launch`
* Allow to configure rate limiting, filtering and internal controller in `franka_control_node`
* **BREAKING** `FrankaHW::FrankaHW` takes additional parameters.
* **BREAKING** Enabled rate limiting and low-pass filtering by default (`franka_control_node.yaml`)
* Publish desired joint state in `/joint_state_desired`
* Removed `effort_joint_trajectory_controller` from `default_controllers.yaml`
* Fixed a bug when switching between controllers using the same `libfranka` interface
## 0.5.0 - 2018-06-28
Requires `libfranka` >= 0.4.0
* **BREAKING** Updated URDF:
* Adjusted maximum joint velocity
* Updated axis 4 hard and soft limits
## 0.4.1 - 2018-06-21
Requires `libfranka` >= 0.3.0
* Added some missing includes to `franka_hw`
* Add support for commanding elbow in Cartesian pose and Cartesian velocity interfaces
## 0.4.0 - 2018-03-26
Requires `libfranka` >= 0.3.0
* **BREAKING** Removed `arm_id` and default `robot_ip` from launchfiles
* **BREAKING** Changed namespace of `franka_control` controller manager
* **BREAKING** Changed behavior of `gripper_action` for compatibility with MoveIt
* Changes in `panda_moveit_config`:
* Updated joint limits from URDF
* Removed `home` poses
* Fixed fake execution
* Add `load_gripper` argument (default: `true`) to `panda_moveit.launch`
* Conditionally load controllers/SRDFs based on `load_gripper`
* Add gripper controller configuration (requires running `franka_gripper_node`)
* Added `mimic` tag for gripper fingers to URDF and fixed velocity limits
## 0.3.0 - 2018-02-22
Requires `libfranka` >= 0.3.0
* **BREAKING** Changed signatures in `franka_hw::FrankaModelHandle`
* **BREAKING** Added epsilon parameters to `franka_gripper/Grasp` action
* Added Collada meshes for Panda and Hand
* Added missing dependencies to `panda_moveit_config` and `franka_example_controllers`
* 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
Requires `libfranka` >= 0.2.0
* Catkin-related fixes for `franka_example_controllers`
* Added missing `<build_export_depend>` for `message_runtime`
## 0.2.1 - 2018-01-30
Requires `libfranka` >= 0.2.0
* Added missing dependency to `franka_example_controllers`
* Lowered rotational gains for Cartesian impedance example controller
## 0.2.0 - 2018-01-29
Requires `libfranka` >= 0.2.0
* Added missing run-time dependencies to `franka_description` and `franka_control`
* Added `tau_J_d`, `m_ee`, `F_x_Cee`, `I_ee`, `m_total`, `F_x_Ctotal`, `I_total`,
`theta` and `dtheta` to `franka_msgs/FrankaState`
* Added new errors to `franka_msgs/Errors`
* Updated and improved examples in `franka_example_controllers`
* Fixed includes for Eigen3 in `franka_example_controllers`
* Fixed gripper state publishing in `franka_gripper_node`
## 0.1.2 - 2017-10-10
* Fixed out-of-workspace build
## 0.1.1 - 2017-10-09
* Integrated `franka_description` as subdirectory
* Fixed dependencies on libfranka
* Fixed RViz config file paths
* Added missing `test_depend` to `franka_hw`
* Added missing CMake install rules
## 0.1.0 - 2017-09-15
* Initial release
File moved
#!groovy
buildResult = 'NOT_BUILT'
def getStages(rosDistribution, ubuntuVersion) {
return {
node('docker') {
step([$class: 'StashNotifier'])
try {
dir('src/franka_ros') {
checkout scm
}
sh 'rm -rf dist'
dir('dist') {
try {
step([$class: 'CopyArtifact',
filter: "libfranka-*-amd64-${ubuntuVersion}.tar.gz",
fingerprintArtifacts: true,
projectName: "SWDEV/libfranka/${java.net.URLEncoder.encode(env.BRANCH_NAME, "UTF-8")}",
selector: [$class: 'StatusBuildSelector', stable: false]])
} catch (e) {
// Fall back to develop branch.
step([$class: 'CopyArtifact',
filter: "libfranka-*-amd64-${ubuntuVersion}.tar.gz",
fingerprintArtifacts: true,
projectName: "SWDEV/libfranka/develop",
selector: [$class: 'StatusBuildSelector', stable: false]])
}
sh """
tar xfz libfranka-*-amd64-${ubuntuVersion}.tar.gz
ln -sf libfranka-*-amd64 libfranka
"""
}
docker.build("franka_ros-ci-worker:${rosDistribution}",
"-f src/franka_ros/.ci/Dockerfile.${rosDistribution} src/franka_ros/.ci").inside('-e MAKEFLAGS') {
withEnv(["CMAKE_PREFIX_PATH+=${env.WORKSPACE}/dist/libfranka/lib/cmake/Franka",
"ROS_HOME=${env.WORKSPACE}/ros-home"]) {
stage("${rosDistribution}: Build & Lint (Debug)") {
sh """
. /opt/ros/${rosDistribution}/setup.sh
src/franka_ros/.ci/debug.sh
"""
junit 'build-debug/test_results/**/*.xml'
}
}
}
if (buildResult != 'FAILED') {
buildResult = 'SUCCESS'
}
} catch (e) {
buildResult = 'FAILED'
}
}
}
}
node {
step([$class: 'StashNotifier'])
}
parallel(
'kinetic': getStages('kinetic', 'xenial'),
'melodic': getStages('melodic', 'bionic'),
)
node {
currentBuild.result = buildResult
step([$class: 'StashNotifier'])
}
# ROS integration for Franka Emika research robots
[![Build Status][travis-status]][travis]
See the [Franka Control Interface (FCI) documentation][fci-docs] for more information.
## License
......
include(CMakeParseArguments)
find_program(CLANG_FORMAT_PROG clang-format-6.0 DOC "'clang-format' executable")
if(CLANG_FORMAT_PROG AND NOT TARGET format)
add_custom_target(format)
add_custom_target(check-format)
endif()
find_program(CLANG_TIDY_PROG clang-tidy-6.0 DOC "'clang-tidy' executable")
if(CLANG_TIDY_PROG AND NOT TARGET tidy)
if(NOT CMAKE_EXPORT_COMPILE_COMMANDS)
message(WARNING "Invoke Catkin/CMake with '-DCMAKE_EXPORT_COMPILE_COMMANDS=ON'
to generate compilation database for 'clang-tidy'.")
endif()
add_custom_target(tidy)
add_custom_target(check-tidy)
endif()
function(add_format_target _target)
if(NOT CLANG_FORMAT_PROG)
return()
endif()
cmake_parse_arguments(ARG "" "" "FILES" ${ARGN})
add_custom_target(format-${_target}
COMMAND ${CLANG_FORMAT_PROG} -i ${ARG_FILES}
WORKING_DIRECTORY ${CMAKE_CURRENT_LIST_DIR}/..
COMMENT "Formatting ${_target} source code with clang-format"
VERBATIM
)
add_dependencies(format format-${_target})
add_custom_target(check-format-${_target}
COMMAND ${CLANG_FORMAT_PROG} -output-replacements-xml ${ARG_FILES} | grep "<replacement " > /dev/null && exit 1 || exit 0
WORKING_DIRECTORY ${CMAKE_CURRENT_LIST_DIR}/..
COMMENT "Checking ${_target} code formatting with clang-format"
VERBATIM
)
add_dependencies(check-format check-format-${_target})
endfunction()
function(add_tidy_target _target)
if(NOT CLANG_TIDY_PROG)
return()
endif()
cmake_parse_arguments(ARG "" "" "FILES;DEPENDS" ${ARGN})
add_custom_target(tidy-${_target}
COMMAND ${CLANG_TIDY_PROG} -fix -p=${CMAKE_BINARY_DIR} ${ARG_FILES}
WORKING_DIRECTORY ${CMAKE_CURRENT_LIST_DIR}/..
DEPENDS ${ARG_DEPENDS}
COMMENT "Running clang-tidy for ${_target}"
VERBATIM
)
add_dependencies(tidy tidy-${_target})
add_custom_target(check-tidy-${_target}
COMMAND ${CLANG_TIDY_PROG} -p=${CMAKE_BINARY_DIR} ${ARG_FILES} | grep . && exit 1 || exit 0
WORKING_DIRECTORY ${CMAKE_CURRENT_LIST_DIR}/..
DEPENDS ${ARG_DEPENDS}
COMMENT "Running clang-tidy for ${_target}"
VERBATIM
)
add_dependencies(check-tidy check-tidy-${_target})
endfunction()
cmake_minimum_required(VERSION 3.4)
project(franka_control)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
find_package(catkin REQUIRED COMPONENTS
controller_interface
controller_manager
franka_hw
franka_msgs
geometry_msgs
message_generation
pluginlib
realtime_tools
roscpp
sensor_msgs
tf
tf2_msgs
)
find_package(Franka 0.7.0 REQUIRED)
catkin_package(
INCLUDE_DIRS include
LIBRARIES franka_state_controller
CATKIN_DEPENDS
controller_interface
franka_hw
franka_msgs
geometry_msgs
pluginlib
realtime_tools
roscpp
sensor_msgs
tf2_msgs
DEPENDS Franka
)
## franka_state_controller
add_library(franka_state_controller
src/franka_state_controller.cpp
)
add_dependencies(franka_state_controller
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)
target_link_libraries(franka_state_controller
${Franka_LIBRARIES}
${catkin_LIBRARIES}
)
target_include_directories(franka_state_controller SYSTEM PUBLIC
${Franka_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)
target_include_directories(franka_state_controller PUBLIC
include
)
## franka_control_node
add_executable(franka_control_node
src/franka_control_node.cpp
)
add_dependencies(franka_control_node
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)
target_link_libraries(franka_control_node
${Franka_LIBRARIES}
${catkin_LIBRARIES}
)
target_include_directories(franka_control_node SYSTEM PUBLIC
${Franka_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)
add_executable(franka_combined_control_node
src/franka_combined_control_node.cpp
)
add_dependencies(franka_combined_control_node
${catkin_EXPORTED_TARGETS}
)
target_link_libraries(franka_combined_control_node
${catkin_LIBRARIES}
)
target_include_directories(franka_combined_control_node SYSTEM PUBLIC
${catkin_INCLUDE_DIRS}
)
## Installation
install(TARGETS franka_state_controller
franka_control_node
franka_combined_control_node
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)
install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
install(DIRECTORY config
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
install(FILES franka_controller_plugins.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
## Tools
include(${CMAKE_CURRENT_LIST_DIR}/../cmake/ClangTools.cmake OPTIONAL
RESULT_VARIABLE CLANG_TOOLS
)
if(CLANG_TOOLS)
file(GLOB_RECURSE SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/src/*.cpp)
file(GLOB_RECURSE HEADERS
${CMAKE_CURRENT_SOURCE_DIR}/include/*.h
${CMAKE_CURRENT_SOURCE_DIR}/src/*.h
)
add_format_target(franka_control FILES ${SOURCES} ${HEADERS})
add_tidy_target(franka_control
FILES ${SOURCES}
DEPENDS franka_control_node franka_combined_control_node franka_state_controller
)
endif()
effort_joint_trajectory_controller:
type: effort_controllers/JointTrajectoryController
joints:
- panda_2_joint1
- panda_2_joint2
- panda_2_joint3
- panda_2_joint4
- panda_2_joint5
- panda_2_joint6
- panda_2_joint7
- panda_1_joint1
- panda_1_joint2
- panda_1_joint3
- panda_1_joint4
- panda_1_joint5
- panda_1_joint6
- panda_1_joint7
constraints:
goal_time: 0.5
panda_2_joint1:
goal: 0.05
panda_2_joint2:
goal: 0.05
panda_2_joint3:
goal: 0.05
panda_2_joint4:
goal: 0.05
panda_2_joint5:
goal: 0.05
panda_2_joint6:
goal: 0.05
panda_2_joint7:
goal: 0.05
panda_1_joint1:
goal: 0.05
panda_1_joint2:
goal: 0.05
panda_1_joint3:
goal: 0.05
panda_1_joint4:
goal: 0.05
panda_1_joint5:
goal: 0.05
panda_1_joint6:
goal: 0.05
panda_1_joint7:
goal: 0.05
gains:
panda_1_joint1: {p: 600, d: 30, i: 0, i_clamp: 1}
panda_1_joint2: {p: 600, d: 30, i: 0, i_clamp: 1}
panda_1_joint3: {p: 600, d: 30, i: 0, i_clamp: 1}
panda_1_joint4: {p: 600, d: 30, i: 0, i_clamp: 1}
panda_1_joint5: {p: 250, d: 10, i: 0, i_clamp: 1}
panda_1_joint6: {p: 150, d: 10, i: 0, i_clamp: 1}
panda_1_joint7: {p: 50, d: 5, i: 0, i_clamp: 1}
panda_2_joint1: {p: 600, d: 30, i: 0, i_clamp: 1}
panda_2_joint2: {p: 600, d: 30, i: 0, i_clamp: 1}
panda_2_joint3: {p: 600, d: 30, i: 0, i_clamp: 1}
panda_2_joint4: {p: 600, d: 30, i: 0, i_clamp: 1}
panda_2_joint5: {p: 250, d: 10, i: 0, i_clamp: 1}
panda_2_joint6: {p: 150, d: 10, i: 0, i_clamp: 1}
panda_2_joint7: {p: 50, d: 5, i: 0, i_clamp: 1}
panda_1_state_controller:
type: franka_control/FrankaStateController
arm_id: panda_1
joint_names:
- panda_1_joint1
- panda_1_joint2
- panda_1_joint3
- panda_1_joint4
- panda_1_joint5
- panda_1_joint6
- panda_1_joint7
publish_rate: 30 # [Hz]
panda_2_state_controller:
type: franka_control/FrankaStateController
arm_id: panda_2
joint_names:
- panda_2_joint1
- panda_2_joint2
- panda_2_joint3
- panda_2_joint4
- panda_2_joint5
- panda_2_joint6
- panda_2_joint7
publish_rate: 30 # [Hz]
position_joint_trajectory_controller:
type: position_controllers/JointTrajectoryController
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
constraints:
goal_time: 0.5
panda_joint1:
goal: 0.05
panda_joint2:
goal: 0.05
panda_joint3:
goal: 0.05
panda_joint4:
goal: 0.05
panda_joint5:
goal: 0.05
panda_joint6:
goal: 0.05
panda_joint7:
goal: 0.05
franka_state_controller:
type: franka_control/FrankaStateController
publish_rate: 30 # [Hz]
joint_names:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
arm_id: panda
robot_hardware:
- panda_1
- panda_2
panda_1:
type: franka_hw/FrankaCombinableHW
arm_id: panda_1
joint_names:
- panda_1_joint1
- panda_1_joint2
- panda_1_joint3
- panda_1_joint4
- panda_1_joint5
- panda_1_joint6
- panda_1_joint7
# Configure the threshold angle for printing joint limit warnings.
joint_limit_warning_threshold: 0.1 # [rad]
# Activate rate limiter? [true|false]
rate_limiting: true
# Cutoff frequency of the low-pass filter. Set to >= 1000 to deactivate.
cutoff_frequency: 1000
# Internal controller for motion generators [joint_impedance|cartesian_impedance]
internal_controller: joint_impedance
# Used to decide whether to enforce realtime mode [enforce|ignore]
realtime_config: enforce
# Configure the initial defaults for the collision behavior reflexes.
collision_config:
lower_torque_thresholds_acceleration: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
upper_torque_thresholds_acceleration: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
lower_torque_thresholds_nominal: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
upper_torque_thresholds_nominal: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
lower_force_thresholds_acceleration: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
upper_force_thresholds_acceleration: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
lower_force_thresholds_nominal: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
upper_force_thresholds_nominal: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
panda_2:
type: franka_hw/FrankaCombinableHW
arm_id: panda_2
joint_names:
- panda_2_joint1
- panda_2_joint2
- panda_2_joint3
- panda_2_joint4
- panda_2_joint5
- panda_2_joint6
- panda_2_joint7
# Configure the threshold angle for printing joint limit warnings.
joint_limit_warning_threshold: 0.1 # [rad]
# Activate rate limiter? [true|false]
rate_limiting: true
# Cutoff frequency of the low-pass filter. Set to >= 1000 to deactivate.
cutoff_frequency: 1000
# Internal controller for motion generators [joint_impedance|cartesian_impedance]
internal_controller: joint_impedance
# Used to decide whether to enforce realtime mode [enforce|ignore]
realtime_config: enforce
# Configure the initial defaults for the collision behavior reflexes.
collision_config:
lower_torque_thresholds_acceleration: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
upper_torque_thresholds_acceleration: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
lower_torque_thresholds_nominal: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
upper_torque_thresholds_nominal: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
lower_force_thresholds_acceleration: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
upper_force_thresholds_acceleration: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
lower_force_thresholds_nominal: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
upper_force_thresholds_nominal: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
joint_names:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
arm_id: panda
# Configure the threshold angle for printing joint limit warnings.
joint_limit_warning_threshold: 0.1 # [rad]
# Activate rate limiter? [true|false]
rate_limiting: true
# Cutoff frequency of the low-pass filter. Set to >= 1000 to deactivate.
cutoff_frequency: 100
# Internal controller for motion generators [joint_impedance|cartesian_impedance]
internal_controller: joint_impedance
# Used to decide whether to enforce realtime mode [enforce|ignore]
realtime_config: enforce
# Configure the initial defaults for the collision behavior reflexes.
collision_config:
lower_torque_thresholds_acceleration: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
upper_torque_thresholds_acceleration: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
lower_torque_thresholds_nominal: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
upper_torque_thresholds_nominal: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm]
lower_force_thresholds_acceleration: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
upper_force_thresholds_acceleration: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
lower_force_thresholds_nominal: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
upper_force_thresholds_nominal: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm]
<library path="lib/libfranka_state_controller">
<class name="franka_control/FrankaStateController" type="franka_control::FrankaStateController" base_class_type="controller_interface::ControllerBase">
<description>A controller that publishes the complete robot state</description>
</class>
</library>
// Copyright (c) 2017 Franka Emika GmbH
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
#pragma once
#include <cstdint>
#include <memory>
#include <vector>
#include <controller_interface/multi_interface_controller.h>
#include <franka_hw/franka_state_interface.h>
#include <franka_hw/trigger_rate.h>
#include <franka_msgs/FrankaState.h>
#include <geometry_msgs/WrenchStamped.h>
#include <realtime_tools/realtime_publisher.h>
#include <sensor_msgs/JointState.h>
#include <tf2_msgs/TFMessage.h>
namespace franka_control {
/**
* Controller to publish the robot state as ROS topics.
*/
class FrankaStateController
: public controller_interface::MultiInterfaceController<franka_hw::FrankaStateInterface> {
public:
/**
* Creates an instance of a FrankaStateController.
*/
FrankaStateController() = default;
/**
* Initializes the controller with interfaces and publishers.
*
* @param[in] robot_hardware RobotHW instance to get a franka_hw::FrankaStateInterface from.
* @param[in] root_node_handle Node handle in the controller_manager namespace.
* @param[in] controller_node_handle Node handle in the controller namespace.
*/
bool init(hardware_interface::RobotHW* robot_hardware,
ros::NodeHandle& root_node_handle,
ros::NodeHandle& controller_node_handle) override;
/**
* Reads the current robot state from the franka_hw::FrankaStateInterface and publishes it.
*
* @param[in] time Current ROS time.
* @param[in] period Time since the last update.
*/
void update(const ros::Time& time, const ros::Duration& period) override;
private:
void publishFrankaStates(const ros::Time& time);
void publishJointStates(const ros::Time& time);
void publishTransforms(const ros::Time& time);
void publishExternalWrench(const ros::Time& time);
std::string arm_id_;
franka_hw::FrankaStateInterface* franka_state_interface_{};
std::unique_ptr<franka_hw::FrankaStateHandle> franka_state_handle_{};
realtime_tools::RealtimePublisher<tf2_msgs::TFMessage> publisher_transforms_;
realtime_tools::RealtimePublisher<franka_msgs::FrankaState> publisher_franka_states_;
realtime_tools::RealtimePublisher<sensor_msgs::JointState> publisher_joint_states_;
realtime_tools::RealtimePublisher<sensor_msgs::JointState> publisher_joint_states_desired_;
realtime_tools::RealtimePublisher<geometry_msgs::WrenchStamped> publisher_external_wrench_;
franka_hw::TriggerRate trigger_publish_;
franka::RobotState robot_state_;
uint64_t sequence_number_ = 0;
std::vector<std::string> joint_names_;
};
} // namespace franka_control
<?xml version="1.0" ?>
<launch>
<!-- The path to a robot description (xacro) file to control -->
<arg name="robot" default="$(find franka_description)/robots/dual_panda_example.urdf.xacro" />
<!-- Additional XACRO args. Be sure to escape colons and equal signs
with backslashes, because XACRO use same syntax as roslaunch:
roslaunch <pkg> <launchfile> robot:=path/to/urdf.xacro args:="foo\:\=bar other\:\=true" -->
<arg name="args" default="" />
<!-- The name of the combined robot, used as control node name -->
<arg name="robot_id" default="combined_panda" />
<!-- The config file containing all parameters for the combined hardware node like the IPs of the robots etc. -->
<arg name="hw_config_file" default="$(find franka_control)/config/franka_combined_control_node.yaml"/>
<!-- Optional arg to manually configure the ips of all robots, overwriting ips that are configured in hw_config_file -->
<!-- The ips must be set as dictionary like {<arm_id_1>/robot_ip: <my_ip_1>, <arm_id_2>/robot_ip: <my_ip_2>} -->
<arg name="robot_ips" />
<!-- The config file containing the parameterization for all controllers to start with this launch file -->
<arg name="controllers_file" default="$(find franka_control)/config/default_combined_controllers.yaml" />
<!-- The space separated list of controllers to start in this launch files. The controllers should be known from the controllers_file -->
<arg name="controllers_to_start" default="panda_1_state_controller panda_2_state_controller"/>
<!-- The list of the joint_states topics of all combined robots to fuse to a complete topic -->
<arg name="joint_states_source_list" default="[panda_1_state_controller/joint_states, panda_2_state_controller/joint_states, panda_1/franka_gripper/joint_states, panda_2/franka_gripper/joint_states]"/>
<node name="$(arg robot_id)" pkg="franka_control" type="franka_combined_control_node" output="screen" required="true" >
<rosparam command="load" file="$(arg hw_config_file)" />
<!-- Add or overwrite manually configured ips -->
<rosparam subst_value="True">$(arg robot_ips)</rosparam>
<param name="robot_description" command="xacro --inorder $(arg robot) $(arg args)" />
</node>
<group ns="$(arg robot_id)">
<rosparam command="load" file="$(arg controllers_file)" />
<node name="hw_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen"
args="$(arg controllers_to_start)"/>
<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="xacro --inorder $(arg robot) $(arg args)" />
<rosparam param="source_list" subst_value="true">$(arg joint_states_source_list)</rosparam>
<param name="rate" value="30"/>
</node>
</group>
</launch>
<?xml version="1.0" ?>
<launch>
<arg name="robot_ip" />
<arg name="load_gripper" default="true" />
<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)" />
<include file="$(find franka_gripper)/launch/franka_gripper.launch" if="$(arg load_gripper)">
<arg name="robot_ip" value="$(arg robot_ip)" />
</include>
<node name="franka_control" pkg="franka_control" type="franka_control_node" output="screen" required="true">
<rosparam command="load" file="$(find franka_control)/config/franka_control_node.yaml" />
<param name="robot_ip" value="$(arg robot_ip)" />
</node>
<rosparam command="load" file="$(find franka_control)/config/default_controllers.yaml" />
<node name="state_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="franka_state_controller"/>
<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">
<rosparam if="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states, franka_gripper/joint_states] </rosparam>
<rosparam unless="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states] </rosparam>
<param name="rate" value="30"/>
</node>
<node name="joint_state_desired_publisher" type="joint_state_publisher" pkg="joint_state_publisher" output="screen">
<rosparam if="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states_desired, franka_gripper/joint_states] </rosparam>
<rosparam unless="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states_desired] </rosparam>
<param name="rate" value="30"/>
<remap from="/joint_states" to="/joint_states_desired" />
</node>
</launch>
<?xml version="1.0"?>
<package format="2">
<name>franka_control</name>
<version>0.7.0</version>
<description>franka_control provides a hardware node to control a Franka Emika research robot</description>
<maintainer email="support@franka.de">Franka Emika GmbH</maintainer>
<license>Apache 2.0</license>
<url type="website">http://wiki.ros.org/franka_control</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 GmbH</author>
<buildtool_depend>catkin</buildtool_depend>
<depend>libfranka</depend>
<depend>controller_interface</depend>
<depend>controller_manager</depend>
<depend>franka_hw</depend>
<depend>franka_msgs</depend>
<depend>geometry_msgs</depend>
<depend>pluginlib</depend>
<depend>realtime_tools</depend>
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
<depend>tf2_msgs</depend>
<depend>tf</depend>
<exec_depend>franka_description</exec_depend>
<exec_depend>franka_gripper</exec_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<export>
<controller_interface plugin="${prefix}/franka_controller_plugins.xml"/>
</export>
</package>
// Copyright (c) 2019 Franka Emika GmbH
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
#include <controller_manager/controller_manager.h>
#include <franka_hw/franka_combined_hw.h>
#include <ros/ros.h>
#include <franka/control_tools.h>
#include <sched.h>
#include <string>
int main(int argc, char** argv) {
ros::init(argc, argv, "franka_combined_control_node");
ros::AsyncSpinner spinner(4);
spinner.start();
ros::NodeHandle private_node_handle("~");
franka_hw::FrankaCombinedHW franka_control;
if (!franka_control.init(private_node_handle, private_node_handle)) {
ROS_ERROR("franka_combined_control_node:: Initialization of FrankaCombinedHW failed!");
return 1;
}
// set current thread to real-time priority
std::string error_message;
if (!franka::setCurrentThreadToHighestSchedulerPriority(&error_message)) {
ROS_ERROR("franka_combined_control_node: Failed to set thread priority to real-time. Error: %s",
error_message.c_str());
return 1;
}
controller_manager::ControllerManager cm(&franka_control, private_node_handle);
ros::Duration period(0.001);
ros::Rate rate(period);
while (ros::ok()) {
rate.sleep();
ros::Time now = ros::Time::now();
franka_control.read(now, period);
cm.update(now, period, franka_control.controllerNeedsReset());
franka_control.write(now, period);
}
return 0;
}
// Copyright (c) 2017 Franka Emika GmbH
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
#include <algorithm>
#include <atomic>
#include <actionlib/server/simple_action_server.h>
#include <controller_manager/controller_manager.h>
#include <franka/exception.h>
#include <franka/robot.h>
#include <franka_hw/franka_hw.h>
#include <franka_hw/services.h>
#include <franka_msgs/ErrorRecoveryAction.h>
#include <ros/ros.h>
using franka_hw::ServiceContainer;
int main(int argc, char** argv) {
ros::init(argc, argv, "franka_control_node");
ros::NodeHandle public_node_handle;
ros::NodeHandle node_handle("~");
franka_hw::FrankaHW franka_control;
if (!franka_control.init(public_node_handle, node_handle)) {
ROS_ERROR("franka_control_node: Failed to initialize FrankaHW class. Shutting down!");
return 1;
}
franka::Robot& robot = franka_control.robot();
std::atomic_bool has_error(false);
ServiceContainer services;
franka_hw::setupServices(robot, node_handle, services);
actionlib::SimpleActionServer<franka_msgs::ErrorRecoveryAction> recovery_action_server(
node_handle, "error_recovery",
[&](const franka_msgs::ErrorRecoveryGoalConstPtr&) {
try {
robot.automaticErrorRecovery();
has_error = false;
recovery_action_server.setSucceeded();
ROS_INFO("Recovered from error");
} catch (const franka::Exception& ex) {
recovery_action_server.setAborted(franka_msgs::ErrorRecoveryResult(), ex.what());
}
},
false);
// Initialize robot state before loading any controller
franka_control.update(robot.readOnce());
controller_manager::ControllerManager control_manager(&franka_control, public_node_handle);
recovery_action_server.start();
// Start background threads for message handling
ros::AsyncSpinner spinner(4);
spinner.start();
while (ros::ok()) {
ros::Time last_time = ros::Time::now();
// Wait until controller has been activated or error has been recovered
while (!franka_control.controllerActive() || has_error) {
franka_control.update(robot.readOnce());
ros::Time now = ros::Time::now();
control_manager.update(now, now - last_time);
franka_control.checkJointLimits();
last_time = now;
if (!ros::ok()) {
return 0;
}
}
try {
// Run control loop. Will exit if the controller is switched.
franka_control.control([&](const ros::Time& now, const ros::Duration& period) {
if (period.toSec() == 0.0) {
// Reset controllers before starting a motion
control_manager.update(now, period, true);
franka_control.checkJointLimits();
franka_control.reset();
} else {
control_manager.update(now, period);
franka_control.checkJointLimits();
franka_control.enforceLimits(period);
}
return ros::ok();
});
} catch (const franka::ControlException& e) {
ROS_ERROR("%s", e.what());
has_error = true;
}
}
return 0;
}
This diff is collapsed.
/**
* @mainpage
* @htmlinclude "manifest.html"
*
* Overview page for Franka Emika research robots: https://frankaemika.github.io
*/
- builder: doxygen
javadoc_autobrief: YES
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment