All Projects → leggedrobotics → Free_gait

leggedrobotics / Free_gait

Licence: bsd-3-clause
An Architecture for the Versatile Control of Legged Robots

Projects that are alternatives of or similar to Free gait

Grl
Robotics tools in C++11. Implements soft real time arm drivers for Kuka LBR iiwa plus V-REP, ROS, Constrained Optimization based planning, Hand Eye Calibration and Inverse Kinematics integration.
Stars: ✭ 105 (-60.08%)
Mutual labels:  robotics, ros, robot, control
Aikido
Artificial Intelligence for Kinematics, Dynamics, and Optimization
Stars: ✭ 133 (-49.43%)
Mutual labels:  robotics, ros, motion-planning
erdos
Dataflow system for building self-driving car and robotics applications.
Stars: ✭ 135 (-48.67%)
Mutual labels:  robot, robotics, ros
Pythonrobotics
Python sample codes for robotics algorithms.
Stars: ✭ 13,934 (+5198.1%)
Mutual labels:  robotics, robot, control
Awesome Robotic Tooling
Tooling for professional robotic development in C++ and Python with a touch of ROS, autonomous driving and aerospace.
Stars: ✭ 1,876 (+613.31%)
Mutual labels:  robotics, ros, robot
Dolly
🤖🐑 It's a sheep, it's a dolly, it's a following robot. Dolly was born to be cloned.
Stars: ✭ 113 (-57.03%)
Mutual labels:  robotics, ros, robot
Rosnodejs
Client library for writing ROS nodes in JavaScript with nodejs
Stars: ✭ 145 (-44.87%)
Mutual labels:  robotics, ros, robot
Webots
Webots Robot Simulator
Stars: ✭ 1,324 (+403.42%)
Mutual labels:  robotics, ros, robot
Ros robotics projects
Example codes of new book ROS Robotics Projects
Stars: ✭ 240 (-8.75%)
Mutual labels:  robotics, ros, robot
the-Cooper-Mapper
An open source autonomous driving research platform for Active SLAM & Multisensor Data Fusion
Stars: ✭ 38 (-85.55%)
Mutual labels:  control, motion-planning, ros
CLF reactive planning system
This package provides a CLF-based reactive planning system, described in paper: Efficient Anytime CLF Reactive Planning System for a Bipedal Robot on Undulating Terrain. The reactive planning system consists of a 5-Hz planning thread to guide a robot to a distant goal and a 300-Hz Control-Lyapunov-Function-based (CLF-based) reactive thread to co…
Stars: ✭ 21 (-92.02%)
Mutual labels:  robot, robotics, motion-planning
ROS-TCP-Connector
No description or website provided.
Stars: ✭ 123 (-53.23%)
Mutual labels:  robot, robotics, ros
Robotics setup
Setup Ubuntu 18.04, 16.04 and 14.04 with machine learning and robotics software plus user configuration. Includes ceres tensorflow ros caffe vrep eigen cudnn and cuda plus many more.
Stars: ✭ 110 (-58.17%)
Mutual labels:  robotics, ros, robot
Cleanit
Open-source Autonomy Software in Rust-lang with gRPC for the Roomba series robot vacuum cleaners. Under development.
Stars: ✭ 125 (-52.47%)
Mutual labels:  robotics, ros, motion-planning
piper
No description or website provided.
Stars: ✭ 50 (-80.99%)
Mutual labels:  robotics, motion-planning, ros
Weloveinterns
中科院软件所智能软件中心实习生社区
Stars: ✭ 143 (-45.63%)
Mutual labels:  robotics, ros, robot
Ev3dev Lang Java
A project to learn Java and create software for Mindstorms Robots using hardware supported by EV3Dev & the LeJOS way.
Stars: ✭ 79 (-69.96%)
Mutual labels:  robotics, ros, robot
Rvd
Robot Vulnerability Database. An archive of robot vulnerabilities and bugs.
Stars: ✭ 87 (-66.92%)
Mutual labels:  robotics, ros, robot
Xpp
Visualization of Motions for Legged Robots in ros-rviz
Stars: ✭ 177 (-32.7%)
Mutual labels:  robotics, ros, motion-planning
scikit-robot
A Flexible Framework for Robot Control in Python
Stars: ✭ 70 (-73.38%)
Mutual labels:  robot, motion-planning, ros

Free Gait

An Architecture for the Versatile Control of Legged Robots

NOTICE: This software is not supported anymore! The authors of this software have changed their affiliation and do not work on this project anymore. Please excuse any inconvenience this might cause. If you are interested in working with the ANYmal robot, please reach out to ANYbotics.

Free Gait Applications

Free Gait is a software framework for the versatile, robust, and task-oriented control of legged robots. The Free Gait interface defines a whole-body abstraction layer to accommodate a variety of task-space control commands such as end effector, joint, and base motions. The defined motion tasks are tracked with a feedback whole-body controller to ensure accurate and robust motion execution even under slip and external disturbances. The application of this framework includes intuitive tele-operation of the robot, efficient scripting of behaviors, and fully autonomous operation with motion and footstep planners.

The source code is released under a BSD 3-Clause license.

Author: Péter Fankhauser
With contributions by: Samuel Bachmann, Dario Bellicoso, Thomas Bi, Remo Diethelm, Christian Gehring

This projected was initially developed at RSL, ETH Zurich.

Build Status

Publications

If you use this work in an academic context, please cite the following publication(s):

  • P. Fankhauser, D. Bellicoso, C. Gehring, R. Dubé, A. Gawel, M. Hutter, "Free Gait – An Architecture for the Versatile Control of Legged Robots", in IEEE-RAS International Conference on Humanoid Robots, 2016. (PDF)

      @inproceedings{Fankhauser2016FreeGait,
          author = {Fankhauser, P{\'{e}}ter and Bellicoso, C. Dario and Gehring, Christian and Dub{\'{e}}, Renaud and Gawel, Abel and Hutter, Marco},
          booktitle = {IEEE-RAS International Conference on Humanoid Robots},
          title = {{Free Gait – An Architecture for the Versatile Control of Legged Robots}},
          year = {2016},
      }
    

Unit Tests

catkin build free_gait_core --no-deps --verbose --catkin-make-args run_tests

Overview

This video shows some of the applications of Free Gait.

Free Gait Notions and Coordinate Systems Free Gait Motion Examples Free Gait Control Scheme
Motions are based on a combination of (possibly multiple) leg motions and a base motion per command (step). The command structure allows to control legged robots in various ways. Motion goals are commanded through the Free Gait API to the whole-body motion controller.

Usage

This video presents an overview over the tools provided in Free Gait.

Free Gait Actions

Free Gait actions are libraries and scripts that define motions using the Free Gait API (for ROS ). For ROS, these actions can be write in any language with a ROS client library using the message and action definitions in free_gait_msgs. For C++, Free Gait provides the free_gait_core library to work with motion definitions and the free_gait_ros for interfacing ROS. To work with Python, use the free_gait_python library. For simple motion definitions, Free Gait supports actions defined in YAML format. For more information about using YAML actions, refer to YAML Scripting Interface.

Free Gait commands are expressed as a combination of leg (in joint or end-effector Cartesian space) and base motions with definition of position, velocity, and/or force/torque targets or trajectories.

Target Trajectory Automatic
Leg motion in joint space JointTarget JointTrajectory LegMode
Leg motion in Cartesian space EndEffectorTarget EndEffectorTrajectory Footstep
Base motion BaseTarget BaseTrajectory BaseAuto

Free Gait actions can be either launched manually or with help of the free_gait_action_loader.

Free Gait Action Loader

The free_gait_action_loader allows to launch actions through a ROS service or ROS action. Currently, the action loader supports YAML motion definitions, Python scripts, and starting ROS launch files for C++ and other libraries.

Run the free_gait_action_loader with

rosrun free_gait_action_loader action_loader.py

The free_gait_action_loader manages the actions and makes sure that only one action is running at the time. To register an action with the free_gait_action_loader, one has to load the action as a ROS plugin.

RQT Free Gait Action

The rqt_free_gait_action package provides a rqt user interface to the free_gait_action_loader. The interface shows the actions organized in collections and allows to preview and send the actions. Additionally, collections can be run as sequence of actions and with a right-click, a collection can be selected as favorite. Favorites are shown as buttons on the top for quick access.




RQT Free Gait Monitor

Once actions are being executed by the Free Gait action server, the rqt_free_gait_monitor shows the progress of the execution and allows to pause and stop the active action.






Free Gait RViz Plugin

Actions can be previewed with the free_gait_rviz_plugin. It takes the current state of the robot and visualizes the motion based on the defined action. This RViz plugin allows to scrub through time and visualize footholds, trajectories, support polygons etc.





YAML Scripting Interface

For simple motion sequences, Free Gait actions can be defined as a sequence of YAML definitions.

For example, this action lifts the right-fore leg of the robot:

adapt_coordinates:
 - transform:
    source_frame: footprint
    target_frame: odom

steps:
 - step:
   - base_auto:
 - step:
   - base_auto:
   - end_effector_target:
      name: RF_LEG
      ignore_contact: true
      target_position:
       frame: footprint
       position: [0.39, -0.22, 0.20]

The adapt_coordinates command transforms motions defined in the source_frame to the target_frame.

FAQ

Actions Are Not Found

If no Free Gait actions are found/loaded, this service call will return empty:

rosservice call /free_gait_action_loader/list_actions "collection_id: ''"

In this case, try initializing rosdep with:

sudo rosdep init
rosdep update
Note that the project description data, including the texts, logos, images, and/or trademarks, for each open source project belongs to its rightful owner. If you wish to add or remove any projects, please contact us at [email protected].