Setup giskard for your own robot - SemRoCo/giskardpy GitHub Wiki

Setup Giskard for a new Robot

Giskard can run in three different control modes:

  • standalone: Giskard acts as a simple kinematic simulator which integrates the generated commands from goals.
  • closed-loop: Controls a robot in real time by talking to velocity controllers and can listen to feedback.
  • open-loop: Uses the simulation mode from standalone to compute trajectories for motions and send them to a real robot.

The selected mode changes how you set up Giskard. In general, you always start by creating a new python file where you instantiate a Giskard instance, pass one configuration objects and then start it. Here is an example for the PR2 in standalone mode:

#!/usr/bin/env python
import rospy

from giskardpy.configs.behavior_tree_config import StandAloneBTConfig
from giskardpy.configs.giskard import Giskard
from giskardpy.configs.iai_robots.pr2 import PR2CollisionAvoidance, WorldWithPR2Config
from giskardpy.configs.qp_controller_config import QPControllerConfig
from giskardpy.configs.robot_interface_config import StandAloneRobotInterfaceConfig

if __name__ == '__main__':
    rospy.init_node('giskard')
    drive_joint_name = 'brumbrum'
    giskard = Giskard(world_config=WorldWithPR2Config(drive_joint_name=drive_joint_name),
                      collision_avoidance_config=PR2CollisionAvoidance(drive_joint_name=drive_joint_name),
                      robot_interface_config=StandAloneRobotInterfaceConfig(
                          [
                              'torso_lift_joint',
                              'head_pan_joint',
                              'head_tilt_joint',
                              'r_shoulder_pan_joint',
                              'r_shoulder_lift_joint',
                              'r_upper_arm_roll_joint',
                              'r_forearm_roll_joint',
                              'r_elbow_flex_joint',
                              'r_wrist_flex_joint',
                              'r_wrist_roll_joint',
                              'l_shoulder_pan_joint',
                              'l_shoulder_lift_joint',
                              'l_upper_arm_roll_joint',
                              'l_forearm_roll_joint',
                              'l_elbow_flex_joint',
                              'l_wrist_flex_joint',
                              'l_wrist_roll_joint',
                              drive_joint_name,
                          ]
                      ),
                      behavior_tree_config=StandAloneBTConfig(publish_tf=True, publish_js=True),
                      qp_controller_config=QPControllerConfig(),
                      additional_goal_package_paths=['my_giskard_config'],
                      additional_monitor_package_paths=['my_giskard_config'])
    giskard.live()

As you can see, Giskard requires 7 config parameters. For all classed, there are several example setups for robots owned by the Institute for Artificial intelligence at the University of Bremen here.

Configuration

World Config

The world config is robot specific, but not mode specific. You can set it up for a robot once and reuse it for all modes. In short, this config defines a tree that describes the world. In simple setups, this means defining a world root link and linking it to the robot urdf with a joint.

Collision Avoidance Config

In the collision avoidance config, you can load a collision matrix srdf, which contains information about which link pairs of a robot don't need to be checked. It also contains a list of links for which collision checking is disabled in general.

Robot Interface Config

The robot interface config defined the interfaces Giskard uses to talk to the robot. In the example above, we are using the predefined StandAloneRobotInterfaceConfig. Since there is no real robot, we have to tell Giskard which joints it should consider as "controlled".

This config is dependent on the behavior tree config in the sense that a robot can only be controlled in closed loop mode, if appropriate interfaces are available and specified here.

Behavior Tree Config

This config tells Giskard how to build its behavior tree. There are 3 predefined configs, one for each control mode. The classes have init parameters for the most common changes people want to make, so you probably don't have to implement your own class.

QP Controller Config

This config is used to change the QP controller which Giskard uses internally. In almost most instances you don't have to implement your own and instead use the predefined one.

additional_goal_package_paths / additional_monitor_package_paths

Specify additional paths where Giskard can find custom monitors and motion goals. The string you write here is the one used in the python import string. For example, if your custom monitor can be imported with from my_giskard_config.my_monitors import MyPayloadMonitor, you have to add my_giskard_config. Giskard will look at all files in that package for monitor implementations. If your files are in some subfolder, you have to add that in the string, e.g. my_giskard_config.sub_folder.

Run Giskard

After Giskard has been initialized, all you need to call giskard.live(). This will start the behavior tree and all ROS interface. When Giskard prints "Giskard is ready", you can start sending goals to Giskard.