Giter VIP home page Giter VIP logo

matthias-mayr / cartesian-impedance-controller Goto Github PK

View Code? Open in Web Editor NEW
200.0 3.0 31.0 3.43 MB

A C++ implementation of Cartesian impedance control for torque-controlled manipulators with ROS bindings.

Home Page: https://matthias-mayr.github.io/Cartesian-Impedance-Controller/

License: BSD 3-Clause "New" or "Revised" License

CMake 3.78% C++ 85.57% Shell 1.20% C 1.03% TeX 8.42%
franka-emika franka-panda gazebo iiwa kuka-iiwa kuka-lbr-iiwa manipulators robotics ros compliant-control

cartesian-impedance-controller's Introduction

Cartesian Impedance Controller

CI rosdoc DOI License

Description

This project is an implementation of Cartesian impedance control for robotic manipulators. It is a type of control strategy that sets a dynamic relationship between contact forces and the position of a robot arm, making it suitable for collaborative robots. It is particularily useful when the interesting dimensions in the workspace are in the Cartesian space.

The controller is developed using the seven degree-of-freedom (DoF) robot arm LBR iiwa by KUKA AG and has also been tested with the Franka Emika Robot (Panda) both in reality and simulation. This controller is used and tested with ROS 1 melodic and noetic.

The implementation consists of a

  1. base library that has few dependencies and can e.g. be directly integrated into software such as the DART simulator and a
  2. ROS control integration on top of it.

Short Pitch at ROSCon:

IMAGE ALT TEXT

http://www.youtube.com/watch?v=Q4aPm4O_9fY

Features

  • Configurable stiffness values along all Cartesian dimensions at runtime
  • Configurable damping factors along all Cartesian dimensions at runtime
  • Change reference pose at runtime
  • Apply Cartesian forces and torques at runtime
  • Optional filtering of stiffnesses, pose and wrenches for smoother operation
  • Handling of joint trajectories with nullspace configurations, e.g. from MoveIt
  • Jerk limitation
  • Separate base library that can be integrated in non-ROS environments
  • Interface to ROS messages and dynamic_reconfigure for easy runtime configuration

Torques

The torque signal commanded to the joints of the robot is composed by the superposition of three joint-torque signals:

  • The torque calculated for Cartesian impedance control with respect to a Cartesian pose reference in the frame of the EE of the robot (tau_task).
  • The torque calculated for joint impedance control with respect to a desired configuration and projected in the nullspace of the robot's Jacobian, so it should not affect the Cartesian motion of the robot's end-effector (tau_ns).
  • The torque necessary to achieve the desired external force command (cartesian_wrench), in the frame of the EE of the robot (tau_ext).

Limitations

  • Joint friction is not accounted for
  • Stiffness and damping values along the Cartesian dimensions are uncoupled
  • No built-in gravity compensation for tools or workpieces (can be achieved by commanding a wrench)

Prerequisites

Required

ROS Controller

We use RBDyn to calculate forward kinematics and the Jacobian.

The installation steps for the installation of the non-ROS dependencies are automated in scripts/install_dependencies.sh.

Controller Usage in ROS

Assuming that there is an initialized catkin workspace you can clone this repository, install the dependencies and compile the controller.

Here are the steps:

cd catkin_ws
git clone https://github.com/matthias-mayr/Cartesian-Impedance-Controller src/Cartesian-Impedance-Controller
src/Cartesian-Impedance-Controller/scripts/install_dependencies.sh
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
catkin_make # or 'catkin build'
source devel/setup.bash

This allows you to add a controller configuration for the controller type cartesian_impedance_controller/CartesianImpedanceController in your ros_control configuration.

Configuration file

When using the controller it is a good practice to describe the parameters in a YAML file and load it. Usually this is already done by your robot setup - e.g. for iiwa_ros that is here. Here is a template of what needs to be in that YAML file that can be adapted:

CartesianImpedance_trajectory_controller:
  type: cartesian_impedance_controller/CartesianImpedanceController
  joints:                               # Joints to control
    - iiwa_joint_1
    - iiwa_joint_2
    - iiwa_joint_3
    - iiwa_joint_4
    - iiwa_joint_5
    - iiwa_joint_6
    - iiwa_joint_7
  end_effector: iiwa_link_ee            # Link to control arm in
  update_frequency: 500                 # Controller update frequency in Hz
  # Optional parameters - the mentioned values are the defaults
  dynamic_reconfigure: true             # Starts dynamic reconfigure server
  handle_trajectories: true             # Accept traj., e.g. from MoveIt
  robot_description: /robot_description # In case of a varying name
  wrench_ee_frame: iiwa_link_ee         # Default frame for wrench commands
  delta_tau_max: 1.0                    # Max. commanded torque diff between steps in Nm
  filtering:                            # Update existing values (0.0 1.0] per s
    nullspace_config: 0.1               # Nullspace configuration filtering
    pose: 0.1                           # Reference pose filtering
    stiffness: 0.1                      # Cartesian and nullspace stiffness
    wrench: 0.1                         # Commanded torque
  verbosity:
    verbose_print: false                # Enables additional prints
    state_msgs: false                   # Messages of controller state
    tf_frames: false                    # Extra tf frames

Startup

To start up with this controller, eventually the controller spawner needs to load the controller. Typically this is baked into the robot driver. For example if using the YAML example above, with iiwa_ros, this can be achieved with command:

roslaunch iiwa_gazebo iiwa_gazebo.launch controller:=CartesianImpedance_trajectory_controller

Changing parameters with Dynamic Reconfigure

If it is not deactivated, the controller can be configured with dynamic_reconfigure both with command line tools as well as the graphical user interface rqt_reconfigure. To start the latter you can run:

rosrun rqt_reconfigure rqt_reconfigure

There are several entries:

  • cartesian_wrench_reconfigure
  • damping_factors_reconfigure
  • stiffness_reconfigure

For applying wrench, the apply checkbox needs to be ticked for the values to be used. Damping and stiffness changes are only updated when the update checkbox is ticked, allowing to configure changes before applying them. Note that the end-effector reference pose can not be set since it usually should follow a smooth trajectory.

Changing parameters with ROS messages

In addition to the configuration with dynamic_reconfigure, the controller configuration can always be adapted by sending ROS messages. Outside prototyping this is the main way to parameterize it.

The instructions below use ${controller_ns} for the namespace of your controller. This can for example be /cartesian_impedance_controller. If you want to copy the example commands 1:1, you can set an environment variable with export controller_ns=/<your_namespace>.

End-effector reference pose

New reference poses can be sent to the topic ${controller_ns}/reference_pose. They are expected to be in the root frame of the robot description which is often world. The root frame can be obtained from the parameter server with rosparam get ${controller_ns}/root_frame.

To send a new reference pose 0.6m above the root frame pointing into the z-direction of it, execute this:

rostopic pub --once /${controller_ns}/reference_pose geometry_msgs/PoseStamped "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: ''
pose:
  position:
    x: 0.0
    y: 0.0
    z: 0.6
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 1.0"

Most often one wants to have a controlled way to set reference poses. Once can for example use a trajectory generator for Cartesian trajectories.

Cartesian Stiffness

In order to set only the Cartesian stiffnesses, once can send a geometry_msgs/WrenchStamped to set_cartesian_stiffness:

rostopic pub --once /${controller_ns}/set_cartesian_stiffness geometry_msgs/WrenchStamped "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: ''
wrench:
  force:
    x: 300.0
    y: 300.0
    z: 300.0
  torque:
    x: 30.0
    y: 30.0
    z: 30.0"

Cartesian Damping factors

The damping factors can be configured with a geometry_msgs/WrenchStamped msg similar to the stiffnesses to the topic ${controller_ns}/set_damping_factors. Damping factors are in the interval [0.01,2]. These damping factors are additionally applied to the damping rule which is 2*sqrt(stiffness).

Stiffnesses, damping and nullspace at once

When also setting the nullspace stiffnes, a custom messages of the type cartesian_impedance_controller/ControllerConfig is to be sent to set_config:

rostopic pub --once /${controller_ns}/set_config cartesian_impedance_controller/ControllerConfig "cartesian_stiffness:
  force: {x: 300.0, y: 300.0, z: 300.0}
  torque: {x: 30.0, y: 30.0, z: 30.0}
cartesian_damping_factors:
  force: {x: 1.0, y: 1.0, z: 1.0}
  torque: {x: 1.0, y: 1.0, z: 1.0}
nullspace_stiffness: 10.0
nullspace_damping_factor: 0.1
q_d_nullspace: [0, 0, 0, 0, 0, 0, 0]"

q_d_nullspace is the nullspace joint configuration, so the joint configuration that should be achieved if the nullspace allows it. Note that the end-effector pose would deviate if the forward kinematics of this joint configuration do not overlap with it.

Cartesian Wrenches

A Cartesian wrench can be commanded by sending a geometry_msgs/WrenchStamped to the topic ${controller_ns}/set_cartesian_wrench. Internally the wrenches are applied in the root frame. Therefore wrench messages are transformed into the root frame using tf.
Note: An empty field frame_id is interpreted as end-effector frame since this is the most applicable one when working with a manipulator.
Note: The wrenches are transformed into the root frame when they arrive, but not after that. E.g. end-effector wrenches might need to get updated.

rostopic pub --once /${controller_ns}/set_cartesian_wrench geometry_msgs/WrenchStamped "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: ''
wrench:
  force:
    x: 0.0
    y: 0.0
    z: 5.0
  torque:
    x: 0.0
    y: 0.0
    z: 0.0"

Trajectories and MoveIt

If handle_trajectories is not disabled, the controller can also execute trajectories. An action server is spun up at ${controller_ns}/follow_joint_trajectory and a fire-and-forget topic for the message type trajectory_msgs/JointTrajectory is at ${controller_ns}/joint_trajectory.

In order to use it with MoveIt its controller configuration (example in iiwa_ros) needs to look somewhat like this:

controller_list:
  - name: ${controller_ns}
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    default: true
    joints:
      - iiwa_joint_1
      - iiwa_joint_2
      - iiwa_joint_3
      - iiwa_joint_4
      - iiwa_joint_5
      - iiwa_joint_6
      - iiwa_joint_7

Note: A nullspace stiffness needs to be specified so that the arm also follows the joint configuration and not just the end-effector pose.

Safety

We have used the controller with Cartesian translational stiffnesses of up to 1000 N/m and experienced it as very stable. It is also stable in singularities.

One additional measure can be to limit the maximum joint torques that can be applied by the robot arm in the URDF. On our KUKA iiwas we limit the maximum torque of each joint to 20 Nm, which allows a human operator to easily interfere at any time just by grabbing the arm and moving it.

When using iiwa_ros, these limits can be applied here. For the Panda they are applied here. Both arms automatically apply gravity compensation, the limits are only used for the task-level torques on top of that.

Documentation

The source code comes with Doxygen documentation. In a catkin workspace it can be built with:

sudo apt-get install ros-$ROS_DISTRO-rosdoc-lite
roscd cartesian_impedance_controller
rosdoc_lite .

It can then be found in the doc folder with doc/html/index.html being the entry point.

The documentation for the public Github repository is automatically built and is deployed at:
https://matthias-mayr.github.io/Cartesian-Impedance-Controller/

Repository and Contributions

The main public code repository is at: https://github.com/matthias-mayr/Cartesian-Impedance-Controller

Issues, questions and pull requests are welcome. Feel free to contact the main author at [email protected] if you are using this implementation.

Citing this Work

A brief paper about the features and the control theory is accepted at JOSS. If you are using it or interacting with it, we would appreciate a citation:

Mayr et al., (2024). A C++ Implementation of a Cartesian Impedance Controller for Robotic Manipulators. Journal of Open Source Software, 9(93), 5194, https://doi.org/10.21105/joss.05194
@article{mayr2024cartesian,
    doi = {10.21105/joss.05194},
    url = {https://doi.org/10.21105/joss.05194},
    year = {2024},
    publisher = {The Open Journal},
    volume = {9},
    number = {93},
    pages = {5194},
    author = {Matthias Mayr and Julian M. Salt-Ducaju},
    title = {A C++ Implementation of a Cartesian Impedance Controller for Robotic Manipulators}, journal = {Journal of Open Source Software}
}

Troubleshooting

Compilation - A required package was not found

catkin build shows this CMake Error:

CMake Error at /usr/share/cmake-3.16/Modules/FindPkgConfig.cmake:463 (message):
  A required package was not found
Call Stack (most recent call first):
  /usr/share/cmake-3.16/Modules/FindPkgConfig.cmake:643 (_pkg_check_modules_internal)
  CMakeLists.txt:12 (pkg_check_modules)

There are missing dependencies. When replacing catkin_ws with your workspace, they can be resolved like this :

cd catkin_ws
src/cartesian_impedance_controller/scripts/install_dependencies.sh
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y

RBDyn Library not found

When starting the controller, this message appears:

 [ControllerManager::loadController]: Could not load class 'cartesian_impedance_controller/CartesianImpedanceController': Failed to load library /home/matthias/catkin_ws/devel/lib//libcartesian_impedance_controller_ros.so. Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: Could not load library (Pocoexception = libRBDyn.so.1: cannot open shared object file: No such file or directory) /gazebo: [ControllerManager::loadController]: Could not load controller 'CartesianImpedance_trajectory_controller' because controller type 'cartesian_impedance_controller/CartesianImpedanceController' does exist.

This happens when a shared library can not be found. They are installed with scripts/install_dependencies.sh. The dynamic linker has a cache and we now manually update it by calling ldconfig after the installation.

Controller crashes

Most likely this happens because some parts of the stack like iiwa_ros or RBDyn were built with SIMD/march=native being turned on and other parts are not. Everything needs to be built with or without this option in order to have working alignment. This package builds without, because it is otherwise cumbersome for people to ensure that this happens across the whole stack.

cartesian-impedance-controller's People

Contributors

faseehcs avatar jsaltducaju avatar kyleniemeyer avatar matthias-mayr avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar

cartesian-impedance-controller's Issues

Passing license check with ros_license_linter

Ideally the repo should pass the ros_license_linter check.

Right now it does not, because of these files:

The following files contain licenses that are not covered by any license tag:
  'README.md': ['CC-BY-SA-4.0']                --> The readme contains a bib entry for the paper
  'res/orcidlink.sty': ['LPPL-1.3c']           --> The stylefile of the JOSS paper
  'src/pseudo_inversion.h': ['LicenseRef-scancode-public-domain']  --> valid

The issue is handled here: boschresearch/ros_license_toolkit#24
Once it is fixed, the Github action could be integrated.

Integration with Dart simulator

hey Matthias,
As you have mentioned that this library can be integrated with dart simulator. I am very new to dart as I have just started tutorials.
Can you throw some light how do I integrate this library with dart simulator?

Secondly:
I want to use iiwa_ros package with dart simulator using CI controller. Only selecting <args="physics" default="dart"/> in gazebo launch would not work right?

Slow execution of (moveit) trajectory

The execution of trajectories generated by moveit seem really slow. Even with high stiffness; translation up to 2000. They work well when executed by a position controller. The movement seems to be slower than commanded, and after finishing, the controller returns a successful execution. However, it is not at the final position yet and the arm still moves closer to the end goal, even after 'finishing' the trajectory. (Tried on Franka Panda/FR3)

Would it be possible to support UR e-series arms?

This is more of a conceptual question. I am happy to jump in to try to get it running on a UR e-series arm, but I am wondering if that would be technically feasible in your opinion (or if it would just be a waste of effort).

Run in the Gazebo and real panda?

Hey,
Thanks for your nice project! I wanna try my own low level controller(cartesian impedance controller and so on) in c++ as the controller plugin just like u have done in this project, but for gazebo simulation. This kind of try can let me familiarize with franka robot. I read the doc Franka Control Interface. The reason for opening this issue is that the used interfaces in Franka Gazebo(Franka_HwSim) and real Franka(Franka_Hw) are not the same. Did you run the simulation on the gazebo? Did you run the controller on the real panda? If i want to run my controller on the real panda, should i also change my code for the real panda because of the Interface(Franka_Hw), even though i can run the controller for simulation?I found that you don't use the Franka_Hw in your controller. It's not the same way as the ones I've seen. I am very confused about the kind of issues right now. I'm looking forward to some of the experiences you can share. Thanks a lot for your time! !

How to control the duration of single step motion in impedance control mode?

Hi Dr. Matthias, thank you very much for your work. I have tried this controller on iiwa simulation and real robot. But now I have a question, how to control the movement duration of a single cloth in the torque control mode? It mainly has the following two purposes:

  1. The speed can be controlled in a wide range of motion to ensure a balance between safety and efficiency.

  2. Strike a balance between pose convergence accuracy and movement duration.
    At present, I simply wrote a class to publish the reference pose, as follows

    pose_pub = nh->advertise<geometry_msgs::PoseStamped>("/iiwa/CartesianImpedance_trajectory_controller/reference_pose",10)

    void iiwa_pose_param_update::set_iiwa_pose_msg() {
    ref_rotation.GetQuaternion(quaternion_x,quaternion_y,quaternion_z,quaternion_w);
    pose_msg.pose.position.x = ref_pose.x();
    pose_msg.pose.position.y = ref_pose.y();
    pose_msg.pose.position.z = ref_pose.z();
    pose_msg.pose.orientation.x = quaternion_x;
    pose_msg.pose.orientation.y = quaternion_y;
    pose_msg.pose.orientation.z = quaternion_z;
    pose_msg.pose.orientation.w = quaternion_w;
    pose_msg.header.stamp = ros::Time::now();
    }

    void * iiwa_pose_param_update::publish_pose_config(const KDL::Frame& ref_frame) {
    ref_pose = ref_frame.p;
    ref_rotation = ref_frame.M;
    this->set_iiwa_pose_msg();
    pose_pub.publish(pose_msg);
    ros::spinOnce();
    ROS_INFO("Published pos message.");
    return nullptr;}

However, in the main program, I can only continue to execute the release topic before it can better converge to the desired pose, and the convergence time is not fixed (affected by the movement distance), as follows

 while (ros::ok()){
     ipu->publish_pose_config(KDL::Frame(KDL::Rotation::RPY(0, M_PI, 0),
                                         KDL::Vector(0.5, 0.0, 0.7)));

 }

Questions are as follows:

  1. I don’t know if this has anything to do with the choice of communication mechanism. Maybe the action communication mechanism can be used to control the single step duration? I'm not sure about this yet, and I still need to understand the action communication mechanism.
  2. Is it possible to manually set the pose convergence threshold and maximum movement duration? In this way, even if the movement time cannot be accurately controlled, the problem of movement accuracy can still be solved.

I would be very grateful if you could provide some suggestions or solutions. In addition, I hope you can correct me if I don't understand your code properly.

Running instruction?

Hi Matthias,

Great contribution to the community you have done :)
I followed your suggestion from your comment in another issue and come have a look.

I have some questions regarding running your codes.

  1. Does it directly work with the FRI-ROS driver on ubuntu 18 and ros melodic?
  2. Could you elaborate on what scripts are to be run in what orders, and what behaviours are to be expected?
    -- For example, start lbr_server (what option?), rosrun/roslaunch something something...

Thank you very much!

gazebo seg fault error

Hi Matthias,
Thank you for the controller. I am trying to use it with IIWA. when I launch gazebo with the impedance controller with the command 'roslaunch iiwa_gazebo iiwa_gazebo.launch controller:=CartesianImpedance_trajectory_controller', I get seg fault and the process dies. I am using ros-noetic.

error_controller

Do you have any inputs on what might be causing the issue?

Thank you

Bimanual cartesian controller

Hello,

First, I have been testing with your controller and actually I like it, so thank you for your work!.

My question is if you ever loaded in gazebo two robots and tried to control them using your actual controller loaded twice for each robot.

Also, I'm considering to create a dual Cartesian controller in order to control both a panda and iiwa14 robots, using your work as base. The idea would be to control both robots in one controller. Should I consider something before starting on this?

Regards,
Mikel

Any ideas for gravity compensation for gripper and workpiece weight ?

I have been using Cartesian-Impedance-Controller, however, I observed there is always an error to the goal state. From my understanding from the repo, we need to command wrenches to compensate the gravity due to tool and workpiece.

Any ideas how to calculate wrenches dynamically during motion to compensate the gravity due to weights of the tool and workpiece?

Test

Hey! nice work.

I'm developing a impedance controller as well, but the robot itself is not much available.
Did you test the impedance controller in simulation or only in real life?

I wanna do it in simulation, is that possible?

Safety and Realibity measures when using Cartesian Impedance Controller

Hi Matthias,

I have been using Cartesian Impedance Contoller with iiwa_ros and also using CI_trajectory_controller/reference_pose or cartesian trajectory planner to send the commands to the robot. The functioning is very impressive, thanks to you.
I want to gain confidence for regular use of the same functionality without actively keeping my awareness to press Emergency stop :p , just in case robot behaves weirdly.
Are their any reliability and safety measures which I can set to keep the robot in confidence even when working very close to human?
There are some safety configurations which I have set up in the KUKA controller such as joint limits, max. cartesian velocities, etc. Can you recommend additional measures please.
Sometimes what happens that,

  1. FRI connection would break while running and restarting the application gives some JAVAlang error. This makes the robot totally in torque control mode with zero stiffness. Due to the errors in load data detemination (multiple trials/ additionally due to have some wires going down from the end-effector), robot does tries to move faster.
  2. Sending the reference_poses to the robot, sometimes robot tries to move very fast. Parameters which Im using are as follows:
    {delta_tau_max: 1.0
    filtering:
    nullspace_config: 0.1
    pose: 0.3
    stiffness: 0.1
    wrench: 0.5 }
  3. What will happen if the IK solution is not available at certain poses? In simulation the robot moves very fast in these situations. Can you please shed some light over it? I tried to check the IK using iiwa_tools over the path computed by cartesin_trajecotry_generator, but Im getting mirror solutions for every next pose. (provided the seed value as per the joint values of the last pose).

Implement compatibilty with rqt_joint_trajectory_controller

This controller is currently not compatible with the rqt_joint_trajectory_controller from ros_control.

To be compatible, these prerequisites must be fulfilled:

For a controller to be compatible with this plugin, it must comply with
the following requisites:
    - The controller type contains the C{JointTrajectoryController}
    substring, e.g., C{position_controllers/JointTrajectoryController}
    - The controller exposes the C{command} and C{state} topics in its
    ROS interface.

Furthermore, this rqt plugin sends a trajectory with a single joint value. This means that real interpolation needs to be implemented by this controller. Currently we assume trajectories with many points and just update the nullspace configuration.

Feel free to send a PR to implement this and/or a reaction in this issue if this is a feature that is needed.

ROS time restrictions

Greetings,
My field of interest is robotics and developing software in ROS for impedance control. My goal is to test my code on two robots, one active robot and one passive. The active robot will try to "push" gently the passive robot, as if by mistake and then try to move accordingly so that it won't actually push it. The interesting fact here is that the parts of the robots that will be in touch are made of metal, that is the surfaces will be hard. For that reason, the computation/refresh time of the package would need to be in the order of milliseconds. My worry is that the ROS environment would not thrive on these restrictions. That's why I would like to ask you whether you have tested your package using this library (consequently and the ROS capabilities) for tests between hard surfaces and what were your time restrictions?

Controller manager freezing when loading the controller

Hi Matthias, great work! I am trying to run the controller on a Franka Emika Panda/FR3 with moveit, i followed the installation instructions but the controller manager freezes when it tries to load the controller. Sorry if this is not a problem directly with your controller, but something on my end. Do you have any idea what causes this? I think https://answers.ros.org/question/284099/controller-spawner-stuck-while-loading/ is related, and it seems to be something about a multi-threaded spinner in the hw iface node, causing a deadlock.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.