Giter Site home page Giter Site logo

ros-controls / ros_controllers Goto Github PK

View Code? Open in Web Editor NEW
547.0 43.0 524.0 2.51 MB

Generic robotic controllers to accompany ros_control

Home Page: http://wiki.ros.org/ros_control

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

CMake 3.45% C++ 91.24% Objective-C 1.96% Python 3.35%

ros_controllers's Introduction

ros_controllers

See ros_control and ros_controllers documentation on ros.org

Build Status

Indigo Kinetic Lunar Melodic Noetic
Build Status Build Status Build Status Build Status Build Status

Branches for source-based installation

ROS Indigo ROS Kinetic ROS Lunar ROS Melodic
indigo-devel kinetic-devel kinetic-devel melodic-devel

Publication

If you find this work useful please give credits to the authors by citing:

  • S. Chitta, E. Marder-Eppstein, W. Meeussen, V. Pradeep, A. Rodríguez Tsouroukdissian, J. Bohren, D. Coleman, B. Magyar, G. Raiola, M. Lüdtke and E. Fernandez Perdomo "ros_control: A generic and simple control framework for ROS", The Journal of Open Source Software, 2017. (PDF)
@article{ros_control,
author = {Chitta, Sachin and Marder-Eppstein, Eitan and Meeussen, Wim and Pradeep, Vijay and Rodr{\'i}guez Tsouroukdissian, Adolfo  and Bohren, Jonathan and Coleman, David and Magyar, Bence and Raiola, Gennaro and L{\"u}dtke, Mathias and Fern{\'a}ndez Perdomo, Enrique},
title = {ros\_control: A generic and simple control framework for ROS},
journal = {The Journal of Open Source Software},
year = {2017},
doi = {10.21105/joss.00456},
URL = {http://www.theoj.org/joss-papers/joss.00456/10.21105.joss.00456.pdf}
}

ros_controllers's People

Contributors

agutenkunst avatar artivis avatar bmagyar avatar bulwahn avatar davetcoleman avatar efernandez avatar fjp avatar fmessmer avatar francofusco avatar graiola avatar jbohren avatar jordan-palacios avatar jspricke avatar k-okada avatar kejxu avatar lucasw avatar maik93 avatar mallanmba avatar martiniil avatar mateus-amarante avatar mathias-luedtke avatar matthew-reynolds avatar miguelprada avatar po1 avatar t045t avatar tappan-at-git avatar tfoote avatar vincentrou avatar wmmc88 avatar wxmerkt 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  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

ros_controllers's Issues

Pulling out hardware_interface_adapter from joint_trajectory_controller into separate package?

We are looking into implementing some controllers of our own. For that, the approach taken in the joint_trajectory_controller package of providing a hardware interface adapter seems to be a good idea, as it makes adapting controllers to different interfaces relatively painless. It seems somewhat ugly to depend on joint_trajectory_controller just to get the hardware interface header, however. I´m thus throwing the idea out there to get it out of the joint trajectory controller into a separate package. Thoughts?

joint_trajectory_controller: Gets a segmentation fault after many calls

I'm using FollowJointTrajectoryAction to control a robot arm when I'm teleoperating it with a joystick. Goals contain a single waypoint, and are sent at a maximum rate of 30 Hz. After about two minutes (~3600 goals sent), a segmentation fault occurs in the joint trajectory controller. This happens even when all the goals are identical. I've tried sending goals only when the positions in the goal change, but that just postpones the segmentation fault. I'm using the joint trajectory controller from hydro-devel, cloned on 10/31/13.

The segmentation fault message:

Segmentation fault (core dumped)
[cerberus/gazebo-4] process has died [pid 5321, exit code 139, cmd /mnt/nvx/jim/catkin_ws/src/gazebo_ros_pkgs/gazebo_ros/scripts/gzserver /mnt/nvx/jim/catkin_ws/src/cerberus/cerberus_gazebo/worlds/srrc_course.sdf __name:=gazebo __log:=/home/jimr/.ros/log/c9dc7342-4326-11e3-b73f-c8600024ec42/cerberus-gazebo-4.log].
log file: /home/jimr/.ros/log/c9dc7342-4326-11e3-b73f-c8600024ec42/cerberus-gazebo-4*.log

The beginning of the stack trace:

Core was generated by `gzserver /mnt/nvx/jim/catkin_ws/src/cerberus/cerberus_gazebo/worlds/srrc_course'.
Program terminated with signal 11, Segmentation fault.
#0  0x000000000042de66 in boost::detail::shared_count::~shared_count() ()
(gdb) where
#0  0x000000000042de66 in boost::detail::shared_count::~shared_count() ()
#1  0x00007fdbc0fbdcea in boost::shared_ptr<realtime_tools::RealtimeServerGoalHandle<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > > >::~shared_ptr (this=0x7fdbc37fd720, __in_chrg=<optimized out>)
    at /usr/include/boost/smart_ptr/shared_ptr.hpp:168
#2  0x00007fdbc0fc16fb in joint_trajectory_controller::JointTrajectoryController<trajectory_interface::QuinticSplineSegment<double>, hardware_interface::PositionJointInterface>::update (this=0x7fdbec0133a0, time=..., period=...)
    at /mnt/nvx/jim/catkin_ws/src/ros_controllers/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller_impl.h:424
#3  0x00007fdbc1f2815f in controller_interface::ControllerBase::updateRequest (
    this=0x7fdbec0133a0, time=..., period=...)
    at /mnt/nvx/jim/catkin_ws/src/ros_control/controller_interface/include/controller_interface/controller_base.h:91
#4  0x00007fdbc1f206a0 in controller_manager::ControllerManager::update (
    this=0x7fdbb4023080, time=..., period=..., reset_controllers=false)
    at /mnt/nvx/jim/catkin_ws/src/ros_control/controller_manager/src/controller_manager.cpp:92
#5  0x00007fdbe0398b7c in gazebo_ros_control::GazeboRosControlPlugin::Update (
    this=0x7fdbb40ed7e0)
    at /mnt/nvx/jim/catkin_ws/src/gazebo_ros_pkgs/gazebo_ros_control/src/gazebo_ros_control_plugin.cpp:210

Here is a program that demonstrates the problem. Replace "cerberus", the controller name, and the joint names with values that will work with your robot. I'm using a Gazebo simulation of Cerberus.

#!/usr/bin/env python

"""joint_traj_test.py"""

import actionlib
import rospy

from control_msgs.msg import FollowJointTrajectoryAction
from control_msgs.msg import FollowJointTrajectoryGoal
from controller_manager_msgs.srv import ListControllers
from trajectory_msgs.msg import JointTrajectory
from trajectory_msgs.msg import JointTrajectoryPoint


def _wait_for_ctrlr(list_ctrlrs, ctrlr_name):
    while True:
        response = list_ctrlrs()
        for ctrlr in response.controller:
            if ctrlr.name == ctrlr_name:
                if ctrlr.state == "running":
                    return
                rospy.sleep(0.1)
                break


rospy.init_node("joint_traj_test")

# Wait for the joint trajectory controller to be in the "running" state.
list_ctrlrs = rospy.ServiceProxy("/cerberus/controller_manager/"
                                 "list_controllers",   ListControllers)
list_ctrlrs.wait_for_service()
_wait_for_ctrlr(list_ctrlrs, "arm_ctrlr")

client = actionlib.SimpleActionClient("/cerberus/arm_ctrlr/"
                                      "follow_joint_trajectory",
                                      FollowJointTrajectoryAction)
client.wait_for_server()

traj_point = JointTrajectoryPoint(positions=[0.0, 1.0, 0.0],
                                  velocities=[0.0] * 3,
                                  accelerations=[0.0] * 3,
                                  effort=[0.0] * 3,
                                  time_from_start=rospy.Duration(1 / 30.0))
traj = JointTrajectory(joint_names=("arm_base_joint", "shoulder_joint",
                                    "elbow_joint"), points=[traj_point])
goal = FollowJointTrajectoryGoal(trajectory=traj)

while not rospy.is_shutdown():
    goal.trajectory.header.stamp = rospy.get_rostime()
    client.send_goal(goal)
    client.wait_for_result()
    rospy.sleep(1 / 30.0)

Joint Trajectory Controller Action Aborting

When sending follow_joint_trajectory commands to the joint_trajectory_controller, the controller only slightly perturbs the robot (in Gazebo simulation) before silently setting the action to aborted. The output information is not very obvious so I could use some pointers in what is going on...

DEBUG ros.joint_trajectory_controller.actionlib: The action server has received a new goal request
DEBUG ros.joint_trajectory_controller: Figuring out new trajectory starting at time 785.600
DEBUG ros.joint_trajectory_controller: Using alternate time base. In it, the new trajectory starts at time 784.825
 WARN ros.joint_trajectory_controller: Dropping first 1 trajectory points out of 62, as they occur before the specified time.
DEBUG ros.joint_trajectory_controller: Trajectory has 62 segments:
- 1 segments will still be executed from current trajectory.
- 1 segment for transitioning between the current trajectory and first point of the input message.
- 60 new segments (61 points) taken from the input message.
DEBUG ros.joint_trajectory_controller.actionlib: Accepting goal, id: /move_group-8-785.598000000, stamp: 785.60
DEBUG ros.joint_trajectory_controller.actionlib: Setting status to aborted on goal, id: /move_group-8-785.598000000, stamp: 785.60
DEBUG ros.joint_trajectory_controller.actionlib: Publishing result for goal with id: /move_group-8-785.598000000 and stamp: 785.60

The effort-based joint position controller can lose commands

If a single command is sent to an effort-based joint position controller via a latched publisher, the command can be lost. Here is the sequence of events:

  1. A position command is published with a latched publisher.
  2. JointPositionController::setCommandCB() is called. It calls JointPositionController::setCommand(), passing it the position.
  3. JointPositionController::setCommand() stores the position in command_struct_.position_.
  4. JointPositionController::update() is about to be called for the first time, so JointPositionController::starting() is called.
  5. JointPositionController::starting() stores the joint's position in command_struct_.position_, overwriting the value received from the publisher.

For a test case, run the following in a directory that's in your ROS path:

git clone https://github.com/wunderkammer-laboratory/ackermann_vehicle.git
roslaunch ackermann_vehicle_gazebo pub_problem.launch

In the Gazebo window that is displayed, you'll see that the vehicle's shock absorbers are not activated, i.e. the chassis is below the wheel's axles. To see how the vehicle should look, run this:

roslaunch ackermann_vehicle_gazebo ackermann_vehicle.launch

This second case works because the shock absorber positions are sent in the main loop, once per second.

I don't know if "the joint controller might lose commands for a short period of time" is the controller's intended behavior. If not, I've found that the problem can be fixed by taking the code above command_.initRT(command_struct_) in JointPositionController::starting() and moving it to the end of JointPositionController::init(), then moving the initialization of sub_command_ to the position immediately following the moved block of code.

Make joint_state_controller robust to system time jumps.

We normally don't perform big discrete jumps in the system time when a robot is running, but a colleague decided to run some tests and see where things broke or stopped working as expected.

One finding is that if the time jumps backwards, the joint_state_controller and other controllers with a similar throttling strategy (like the force_torque_sensor_controller and the imu_sensor_controller) will stop publishing messages until the system time catches up with the backwards jump.

I would consider it expected behavior to keep on publishing at the specified rate, with the new offset timestamps.

Of course, downstream functionality (like the tf buffer) will likely be affected by such system time changes, but if we limit our scope to the joint_state_controller, it makes sense in my mind to preserve the expected topic publish rate.

Pan tilt look-at controller

We've shipped a number of flir PTUs, as well as some Axis IP cameras with integrated pan-tilt— it'd be great to have a controller with interfaces for look at, follow, etc.

Does something like this exist?

Hydro release is stuck at 0.7.2?

The hydro release version is still 0.7.2, and it's missing alot of features (e.g. frame id parametrization for base frame). Would appreciate it if a release can be pushed to the build farm.

Proper repository location?

If we want this to be a "ROS Standard" of sorts, should it probably live under one of the ros-* organization?

[joint_state_controller] Allow to publish joints not present in RobotHW

Inspired by ros-simulation/gazebo_ros_pkgs#141.

Robots sometimes have joints that can't be controlled, or don't even have sensing devices like encoders. A typical example would be a non-driven caster wheel.

In simulated scenarios the state of such joints can be reconstructed as one can add sensors for free, but this can be a problem with real hardware. If no state is available for these joints, ROS tools like tf and the Rviz plugins that depend on it will fail to reconstruct parts of the robot.

One possibility to address this issue would be to extend the joint_state_controller to publish additional joints with a predefined constant value. A controller configuration file could look like so:

joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 50

  # This is the new part that this ticket would address. It's optional
  extra_joints:
    foo_joint: 0.0 # Name: position
    bar_joint: 0.5

Implementation-wise, one would have to take care that there is no overlap between the robot joints and the extra ones.

Joint trajectory controller: Keep executing trajectory when aborted?

The joint trajectory controller implements a behavior inherited from its predecessor that I'd like to discuss. Currently, when a trajectory goal is aborted because of a (path or goal) tolerance violation, its execution is not canceled, but actually keeps on going as best as possible. The first time I saw this it struck me as unexpected behavior, but I learned to live with it. Now that I'm documenting the controller in the ros wiki, the issue came back to my mind.

I think that a good safety layer should not live in the controllers but in software closer to the hardware (enforcing joint limits, reflex emergency behaviors, etc.) and mechanical levels (low inertia, passive compliance, soft covers ,etc.).

For now I'm just stating the expected controller behavior clearly in the doc, and that the controller is not intended to enforce low level safety.

Any thoughts on this?.

missing dependency in velocity_controllers on urdf is breaking build

I believe it was relying on an implicit dependency that has been cleaned up.

http://jenkins.ros.org/view/IbinS32/job/ros-indigo-velocity-controllers_binarydeb_saucy_i386/25/console

[ 33%] Building CXX object CMakeFiles/velocity_controllers.dir/src/joint_velocity_controller.cpp.o
/usr/lib/ccache/c++   -DROSCONSOLE_BACKEND_LOG4CXX -DROS_PACKAGE_NAME=\"velocity_controllers\" -Dvelocity_controllers_EXPORTS -g -O2 -fstack-protector --param=ssp-buffer-size=4 -Wformat -Werror=format-security -D_FORTIFY_SOURCE=2  -O2 -g -DNDEBUG -fPIC -I/tmp/buildd/ros-indigo-velocity-controllers-0.9.0-0saucy-20141102-0505/include -I/opt/ros/indigo/include    -o CMakeFiles/velocity_controllers.dir/src/joint_velocity_controller.cpp.o -c /tmp/buildd/ros-indigo-velocity-controllers-0.9.0-0saucy-20141102-0505/src/joint_velocity_controller.cpp
/usr/bin/cmake -E cmake_progress_report /tmp/buildd/ros-indigo-velocity-controllers-0.9.0-0saucy-20141102-0505/obj-i686-linux-gnu/CMakeFiles 4
[ 66%] Building CXX object CMakeFiles/velocity_controllers.dir/src/joint_position_controller.cpp.o
/usr/lib/ccache/c++   -DROSCONSOLE_BACKEND_LOG4CXX -DROS_PACKAGE_NAME=\"velocity_controllers\" -Dvelocity_controllers_EXPORTS -g -O2 -fstack-protector --param=ssp-buffer-size=4 -Wformat -Werror=format-security -D_FORTIFY_SOURCE=2  -O2 -g -DNDEBUG -fPIC -I/tmp/buildd/ros-indigo-velocity-controllers-0.9.0-0saucy-20141102-0505/include -I/opt/ros/indigo/include    -o CMakeFiles/velocity_controllers.dir/src/joint_position_controller.cpp.o -c /tmp/buildd/ros-indigo-velocity-controllers-0.9.0-0saucy-20141102-0505/src/joint_position_controller.cpp
In file included from /tmp/buildd/ros-indigo-velocity-controllers-0.9.0-0saucy-20141102-0505/src/joint_position_controller.cpp:43:0:
/tmp/buildd/ros-indigo-velocity-controllers-0.9.0-0saucy-20141102-0505/include/velocity_controllers/joint_position_controller.h:70:24: fatal error: urdf/model.h: No such file or directory
 #include <urdf/model.h>
                        ^
compilation terminated.

non-conventional control-error sign direction

As a new user of the position and velocity controllers, I was confused by the non-conventional sign of the controller error term in the position and velocity controllers. I would expect the controller error to be defined as (reference - actual) or (desired - actual) as is shown in the "PID_control" entry of wikipedia ((http://en.wikipedia.org/wiki/PID_controller)); and standard textbooks including http://books.google.com/books/?id=EFgOQABEBjIC and http://books.google.com/books?id=vlMl-j_cWW4C.

Correcting the sign of these controller error terms to conventional use would also require changing the sign of the error terms in ros_control/control_toolbox/src/pid.cpp to keep the standard use of positive controller gains.

If there is a reason for not using what appears to be the dominant sign convention in robotics, we should add comments as to why this choice of control error signs is made in this code and in the API documentation.

odom tf publishing should be optional in diff_drive_controller

See the setup tutorial for robot_localization:

http://wiki.ros.org/robot_localization/Tutorials/Preparing%20Your%20Sensor%20Data#Odometry

REP-105 states that the odom -> base_link tf should come from "an odometry source". To my reading this says it could be diff_drive_controller or a higher level component which also takes in IMU data.

I suggest a default-true parameter, ~enable_odom_tf. If that's agreeable, I can implement it.

@bmagyar

Release 0.7.0

All,

I'd like to release ros_controllers 0.6.1 into hydro, to make the diff_drive_controller and gripper_action_controller packages available as binaries. Are there any blockers against releasing before the end of the week?.

I'd also like to do the initial indigo release soon, but it can be done after dealing with hydro.

Velocity Controller behavior when vel=0

Hi guys,

What is the desired behavior of a velocity controller when its setpoint velocity is 0? It seems that if you just have a PID controller trying to maintain 0 velocity on the joint, as is the case with ros_controllers/effort_controllers/joint_velocity_controller.cpp, your joint will slowly drift with error to a gravity-neutral state. For example, a robot arm will gradually fall down until it reaches its joint limits.

A solution I just implemented is to have the velocity controller switch to a "position-controller" mode when its set to 0 velocity, so as to maintain position and not drift.

Is this a feature I should try to merge into the default velocity_controller? Should it be an option in the init() function? Off or on by default?

Ability to specify namespace of robot_description

In ros_controllers/effort_controllers/src/joint_position_controller.cpp the name of the robot description on the parameter server is hard coded. This is not good for multi-robot systems, such as in simulation using Gazebo:

if (!urdf.initParam("robot_description")){

We need a way to pass a robot_description parameter when starting a controller so that it can be customized. This would need to be done at initRequest(..) in

ros_control/controller_interface/include/controller_interface/controller.h

And then at loadController(..) in

ros_control/controller_manager/src/controller_manager.cpp

Skid steer controller

This is being partly tracked in #55, but I'm especially interested in plans for a skid steer controller, for example for Husky, and similar vehicles.

I've started experimenting a bit with diff_drive_controller, and I like how it's set up— I'll start there, but there a couple big missing pieces to make it suitable for use as a skid steer controller:

  • close loop around vel feedback from an IMU
  • allow for more than one left-side and right-side wheel joint
  • estimate slip, and feed that forward; provide a parameter to initialize the estimate

Would it be worthwhile trying to add this stuff to diff_drive_controller, or should a brand new skid_steer_controller be created? I believe these things would benefit a differential-drive chassis as well, and there'd be the obvious win of shared tests, tutorials, documentation, etc.

I don't have the resources to take on a major project myself in the short term, but I'd be delighted to collaborate on it with someone, or contribute some of these things to diff_drive_controller with design guidance.

Hydro Branch?

ros_controls has a hydro-devel but ros_controllers does not yet. should we add it?

We need mobile base controllers

All,

To make the ros_controll(ers) project appealing to a larger user base, we need to offer functionality needed by that user base, and controllers are a big part of that. Currently, the list of available general-purpose controllers is still quite limited, and we have a big zero on mobile base / vehicle controllers.

I've convinced a colleague to make a diff-drive controller that should land sometime soon, but I wonder about the interest and generality of other implementations.

Interest

Does it make sense to have mobile base controllers inside the (possibly high-frequency) controller_manager loop, or is it enough to control individual wheels with low-level single-joint controllers?. Many navigation scenarios have relatively slow dynamics, but I can imagine many scenarios (self-driving cars!) having requirements for faster dynamics.

Further, having a single ros_control plugin that takes in higher level navigation commands results in simpler deployments than single_joint controllers + an additional node for translating navigation commands to joint commands.

Generality

Implementations like the diff-drive generalize well to multiple robot platforms. Does the same apply to an Ackermann-type controller, are they easily configurable (@jim-rothrock, @jack-oquin)?. How about omnidirectional bases?, these seem more complex to generalize, is it the case?. Are there other controller types that would be of general interest?.

Joint trajectory controller interface

Hi all!
I have hardware that controls by position and velocity together in one command. So i use my own JointHandle analog:

class MyJointHandle : public hardware_interface::JointStateHandle
{
public:
  // ...
  void setCommand(double position, double velocity)
  {
    //...
  }
private:
  double* pos_cmd_;
  double* vel_cmd_;
};

I try to use joint_trajectory_controller::JointTrajectoryController, but it can work only with hardware_interface::JointHandle. But I think it can be improved by a little modification in files:

hardware_interface/internal/hardware_resource_manager.h

@@ -79,6 +79,9 @@
 class HardwareResourceManager : public HardwareInterface, public ResourceManager<ResourceHandle>
 {
 public:
+
+  typedef ResourceHandle ResourceHandleType;
+
   /** \name Non Real-Time Safe Functions
    *\{*/

joint_trajectory_controller/joint_trajectory_controller.h

@@ -171,10 +171,11 @@
   typedef typename Segment::Scalar Scalar;

   typedef HardwareInterfaceAdapter<HardwareInterface, typename Segment::State> HwIfaceAdapter;
+  typedef typename HardwareInterface::ResourceHandleType JointHandle;

   bool                                         verbose_;            ///< Hard coded verbose flag to help in debugging
   std::string                                  name_;               ///< Controller name.
-  std::vector<hardware_interface::JointHandle> joints_;             ///< Handles to controlled joints.
+  std::vector<JointHandle>                     joints_;     ///< Handles to controlled joints.

joint_trajectory_controller/hardware_interface_adapter.h

@@ -55,7 +55,7 @@
 class HardwareInterfaceAdapter
 {
 public:
-  bool init(std::vector<hardware_interface::JointHandle>& joint_handles, ros::NodeHandle& controller_nh)
+  bool init(std::vector<typename HardwareInterface::ResourceHandleType>& joint_handles, ros::NodeHandle& controller_nh)
   {
     return false;
   }

Could you improve that. Thanks.

Messages are duplicated

I just noticed that this repo has a "controller_msgs" package, which is a generic port of the pr2_controller_msgs -- however, it should be noted that the Arm Navigation (and now MoveIt) team have already created a generic port -- which is already released: https://github.com/ros-planning/control_msgs. Perhaps we can use that instead of creating more duplication?

Issue with sample logic for joint_trajectory_controller in trajectory_interface.h

https://github.com/ros-controls/ros_controllers/blob/indigo-devel/joint_trajectory_controller/include/trajectory_interface/trajectory_interface.h#L138

If the findSegment returns end(), which it does for time preceding trajectory, the function
returns it; for it = trajectory.end(). This causes error in
https://github.com/ros-controls/ros_controllers/blob/indigo-devel/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller_impl.h#L398

  1. For preceding time should we add return trajectory.front(); at L150 of trajectory_interface.h?
  2. Given operation of findSegment, how do we differentiate between a time preceding segment, and an actual failure to maintain a valid stopHold position?
    The logic in sample, appears to assume preceding time and cause jump in state from end to beginning.

Velocity Position Controller

Greetings,

I've fallen behind in tracking the recent changes to ros_controllers, particularly a velocity-position-controller. My original attempt at implementing one last year is very out of date. I'm trying to re-vamp the Baxter controllers that I created all of this for. Here is what I've gleemed just now from lost of Github discussions:

It seems most of the original features were finally merged in:
#117
#116

Except this one:
#115

Which will be replaced by:
pal-robotics-forks#41

Question: can we get the joint_mode_controller merged soon?

@brawner In the meantime, I'm going to remove my branch velocity_position_controller since all these features have been replaced, and because, embarrassingly, I made a bad commit to it. I have replaced it with a hydro-only version: https://github.com/ros-controls/ros_controllers/tree/hydro-velocity-pos-controller

Cleanup Branches

I'd like to cleanup the branches in this repo, feedback welcomed:

fuerte-dev --> fuerte-devel
fuerte - REMOVE - this is the same as fuerte-dev except behind one commit
groovy --> groovy-devel
hydro-devel - keep
master - REMOVE - this is behind hydro-devel by a few commits and not really needed

the "devel" name is a standard the ROS community seems to have settled on

typo: perido --> period

I noticed some typos where "period" is misspelled as "perido" in ros_controllers / effort_controllers / src / joint_velocity_controller.cpp

trajectory_interface includes missing from .deb install?

When trying to implement a specialization of the JointTrajectoryController, I want to use trajectory_interface::QuinticSplineSegment<double> for one of the template parameters. It appears the whole trajectory_interface subfolder is missing from the .deb install (12.04/Hydro/AMD64) of ros-hydro-joint-trajectory-controller, however. Or am I just overseeing something?

hold position behavior in face of steady state error

We're seeing an issue on robot where a joint is physically unable to reach desired position due to actuator force limitation. This results in a steady state error.

Thus we get a constant control command= k_p * error.

When the trajectory enters the setHoldPosition it uses getPosition (actual position) on https://github.com/ros-controls/ros_controllers/blob/indigo-devel/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller_impl.h#L689
This takes error to zero, and reduces the servo command value causing a perturbation in the system.

For cases with potential steady state error (e.g. holding a heavy load), should we not hold to the previous desired position to provide constant control.

Only on controller (re)start should we initialize desired position equal to the actual position.

[rqt] Ability to hide controller_manager + controller selectors

This is something that has been slightly annoying me for some time, and I wanted to state it for the record.

The current set of existing rqt plugins are great in the sense that they offer the flexibility to choose any controller from any controller_manager, as exemplified below:

rqt_controller
rqt_controller1

This is great, but once you select a controller, it might be a while until you decide to change controllers again. In the meantime, you're uselessly taking up a non-negligible amount of screen real estate.

I'd like to ask what means of dealing with this issue would appeal the most, or if on the other side, this is not a big problem for you. Two alternatives I can think of are:

  • Put the controller_manager + controller selectors inside a collapsible element that has a minimum footprint when collapsed, but still shows a label of what it contains. This is the most visible option.
  • Put the selectors inside a configuration form accessible from the top-right of the main plugin form (see below). This is a low-visibility option.
    top_right

Joint trajectory controller: Change default for stop_trajectory_duration parameter.

The stop_trajectory_duration parameter of the controller currently defaults to 0.5s. I think it would be best to default it to zero. Since this potentially changes behavior, should I defer the change to Indigo or can it be considered small enough to make it to Hydro?.

Parameter doc follows:

When starting the controller or canceling a trajectory, position hold mode is entered. This parameter specifies the time it takes to bring the current state (position and velocity) to a stop. Its value can be greater or equal than zero.

trajectory_controller for velocity hardware_interface

I see in the README for the (sweet) new trajectory controller

Position and effort control joint interfaces provided by default.

What is stopping me from implementing a hardware_interface_adapter for a VelocityJointInterface? Is there a reason you haven't made it yet, or did you just not have the need?

From what I can tell I can just copy the effort hardware_interface_adapter, and change the PID line to say something like:

const double command = pids_[i]->computeCommand(state_error.velocity[i], period);

I have a robot that only takes position and velocity commands and I believe using velocity is always the better option for controls (is this true?).

Thanks!

No way to remap controller topics

Most problematic with diff_drive_controller, as it means your main command topic ends up as /my_velocity_controller/cmd_vel rather than /cmd_vel. If it's your own controller manager, you can pass remaps into the NodeHandle, but none of that works if it's Gazebo's.

One option is for controllers to just parameterize key topic names, but remapping is an important aspect of ROS's modularity strategy— not having this work in a standardized way seems undesirable.

In the short term, I can just use a topic_tools/relay, but that seems like a pretty non-optimal strategy as well.

Thoughts?

Jogging Command Controller

Would anyone be interested in a jogging command controller I developed?
https://github.com/gt-ros-pkg/ros_controllers/tree/jogging-ctrl/jogging_command_controller

The premise is simple, each joint in the controller is given a command topic. The value to be published is a signed float indicating the direction and maximum velocity the joint should move. The joint accelerates constantly until the max velocity is reached, and then continues moving at the max velocity. The joint keeps moving until a command of 0.0 is given.

Heartbeat monitoring is included as a safety precaution. If the joint does not keep receiving the same command before the heartbeat timeout, or receives a different command from the one it's executing, the joint decelerates until stopped.

A jogging command rqt interface is also included which allows one to both monitor the current joint positions and use buttons to jog the joints. Screenshots of this interface are below.

Everything is a little rough around the edges, and I've made significant changes to the joint_trajectory_controller (see #125) which may need to be either removed or reworked. I'm just looking to see what the demand is here for this.

jogging_gui_1
jogging_gui_2
jogging_gui_3

Making room for mecanum_drive_controller

Hi guys,

I am currently developping a mecanum_drive_controller which (as its name states) will take a twist as input and generate desired wheel velocities. From what I have seen this class will be rather close to diff_drive_controller. So I was thinking of factoring the common code out into a drive_controller class (from which diff_drive_controller and mecanum_drive_controller would derive). It does not look like a big issue, but I was wondering how you would welcome this proposition... If you consider its worth the effort, then I'll make a proposition in a fork of mine, otherwise no worries I'll do a completely separate package in a repo of mine.

Just let me know what you think.

Thanks,

Antoine.

release for indigo

The effort_controllers has been patched but not released into indigo. 7bd1340

This will get rid of a bunch of failing jobs.

Derivative error issue in the effort-based joint position controller

I have found that joints that use the effort-based joint position controller don't settle as quickly as I would expect. Here is a test case:

  1. Go to a directory in your ROS path.
  2. git clone https://github.com/jack-oquin/ackermann_teleop.git
  3. git clone https://github.com/wunderkammer-laboratory/ackermann_vehicle.git
  4. roslaunch ackermann_vehicle_gazebo ackermann_vehicle.launch namespace:=/ cmd_timeout:=0
  5. rosrun ackermann_qt qteleop.py

Use the GUI to drive the vehicle back and forth. Most important, click the "brake" button to bring the vehicle to a sudden stop. You'll see the chassis oscillate quite a bit, as if the shock absorbers aren't doing enough damping.

If you go into joint_position_controller.cpp and remove vel_error from the call to computeCommand(), then rebuild and drive the vehicle again, you'll notice that the shock absorbers have much better damping characteristics. In fact, they are doing exactly what I'd expect, given their parameters. Perhaps JointPositionController::update() could be modified so that it would call the two-parameter version of computeCommand() if the command originated from a call to setCommandCB().

FindPackage xacro in groovy

Hi,

I just updated my package and recognized that catkin_make did not work anymore under groovy (I have no idea if it runs with hydro...).

The problem is that there is no FindXacro which is needed for FindPackage
I solved the problem on my machine by commenting out the xacro from the FindPackage call (Line 67)

for me it seems like xacro is not needed as package (the catkin dependency works...) so it can surely be removed...

greetings

Benjamin

Just released 0.5.4

There have been a lot of fixes that were causing issues with downstream packages, releasing new tag to the build farm.

Release 0.5.3

I think the joint_trajectory_controller is ready for prime time, so I prepared the 0.5.3 release, but since I don't have push access to the ros_controllers gbp, I can't do the final bloom release step

bloom-release ros_controllers --track hydro --rosdistro hydro

So, could someone with push access ( @ahendrix, @davetcoleman ) either:

  • Grant me push access, or
  • Run the above bloom-release command in my stead.

Joint trajectory controller: Send empty msg through action interface

I just discovered that sending an empty message through the action interface does not have the same behavior as PR2's JointTrajectoryActionController:

  • PR2: Reject goal because joint list (empty) doesn't match those of the controller.
  • ros_controllers: Accept goal and have the same effect as sending an empty msg trough the topic interface: cancel all queued trajectory segments.

In the ros_controllers case, an unexpected behavior of its current implementation is that after accepting the empty goal, it remains active. Not very intuitive. I'm opting for maintaining the behavior of the PR2 controller, maybe someone even depends on that.

[joint_trajectory_controller] Purpose of some warning statements

I'm observing the following log output while using the joint_trajectory_controller:

[ WARN] [1385987384.325046066]: Dropping all 1 trajectory points, as they occur before the specified time of 1385987384.327102
[ WARN] [1385987384.325116861]: Last trajectory point: 0.060309278

The fact that the statements are logged is expected, no problem there. What I don't understand well is the purpose of the last statement, i.e., what can I make of it?. From the implementation, I can see that the 0.0603... value is the time_from_start of the last point in a command trajectory, but this is not evident from the log statement. Also, the two WARN messages are printing data that can't be related together: The first one is a time (absolute), while the second is a duration (relative).

What was the original intent when the Last trajectory point: statement was added?.

@davetcoleman

Release 0.7.3 into hydro and 0.9.0 into indigo

I'm planning on making a simultaneous release of ros_controllers into hydro (0.7.2 → 0.7.3) and indigo (0.8.2 → 0.9.0) early next week. Prerelease tests are passing on both branches. If there are any bugfixes that you would like to see in these releases, please let me know.

Complete description for position interface

@adolfo-rt, could you provide please the complete description for the position interface of the joint_trajectory_controller on this page? The complete is provided for the effort interface but I know they are not exactly the same (no PID gains, for example).

Thanks!

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.