Skip to content

Tools for learning from demonstration using DMP framework under ROS

License

Notifications You must be signed in to change notification settings

ARQ-CRISP/ros_dmp_tools

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

1 Commit
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

ROS DMP Tools

Tools for learning from demonstration using dynamical movement primitives (DMP) framework under robot operating system (ROS).

Currently, it uses the open-source DMP implementation of stulp/DMPBBO. It depends on Eigen3 library.

Installation

Tested on Ubuntu 16.04, ROS-Kinetic

Usage

This package contains several ROS nodes and classes for recording, learning and reproducing demonstrations.

Recording:

Recording is done using a TrajectoryRecorder object. It listens to the topic of a generic message type (RecordState.msg) using a StateListener object. StateListener is a template publisher, that publishes the state as RecordState.msg. An example implementation of StateListener is JointStateListener.

Example usage of TrajectoryRecorder:

TrajectoryRecorder trajectory_recorder(&node_handle);

// start a state listener of choice
state_listener_ = new JointStateListener(&node_handle);

state_listener_->startListening();
trajectory_recorder.startRecording(state_size_, duration_, step_count_);

// Keep the node running
ros::spin();

The trajectory is saved as a "traj.txt" file at the end of the given duration_ (seconds).

Learning:

Learning can be done using a train_dmp node:

roslaunch dmp_tools train.launch dmp_name:=mydmp.xml trajectory_name:=mytraj.txt

It will read the mytraj.txt file in the catkin workspace directory. It will produce a mydmp.xml file in the ~/.ros directory. File names may include the directory path optionally.

Parameters of train:

  • dmp_type (0): Type of DMP implementation of DMPBBO. Integer.
  • scaling_type (0): Type of force term scaling of DMPBBO. Integer.
  • basis_count (30): Number of basis functions to form the forcing term.
  • intersection (0.56): Ratio of intersection between basis functions.
  • save_details (true): Flag to save and visualize extra info.

Reproducing:

DmpLoader class can be used for loading a saved trajectory:

// Creating the object
string dmp_filename = "dmp.xml";
DmpLoader* dmp_loader_ = DmpLoader(dmp_filename);
// Creating a trajectory
// Inputs: init_state_, goal_state_, step_count_, duration_
// Outputs: ts (time-step vector), qs, qds, qdds (q: state variable, d: dot/derivative)
dmp_loader_->setInitialState(init_state_);
dmp_loader_->setGoalState(goal_state_);
dmp_loader_->createTrajectory(step_count_, duration_, ts, qs, qds, qdds);

About

Tools for learning from demonstration using DMP framework under ROS

Resources

License

Stars

Watchers

Forks

Packages

No packages published