Skip to content

Commit

Permalink
(doc/CMakeLists, AutoBalancer, Stabilizer, KalmanFilter, RemoveForceS…
Browse files Browse the repository at this point in the history
…ensorLinkOffset, ImpedanceController) : Update documentation for unstable RTC
  • Loading branch information
snozawa committed Sep 27, 2014
1 parent d8f760d commit 62a5386
Show file tree
Hide file tree
Showing 11 changed files with 402 additions and 79 deletions.
9 changes: 9 additions & 0 deletions doc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,11 @@ set(input_files package.h utilities.h
../rtc/VirtualCamera/VirtualCamera.txt
../rtc/VirtualForceSensor/VirtualForceSensor.txt
../rtc/WavPlayer/WavPlayer.txt
../rtc/Stabilizer/Stabilizer.txt
../rtc/AutoBalancer/AutoBalancer.txt
../rtc/KalmanFilter/KalmanFilter.txt
../rtc/ImpedanceController/ImpedanceController.txt
../rtc/RemoveForceSensorLinkOffset/RemoveForceSensorLinkOffset.txt
../lib/io/iob.h
../idl/CollisionDetectorService.idl
../idl/DataLoggerService.idl
Expand All @@ -37,6 +42,10 @@ set(input_files package.h utilities.h
../idl/StateHolderService.idl
../idl/TimeKeeperService.idl
../idl/WavPlayerService.idl
../idl/AutoBalancerService.idl
../idl/StabilizerService.idl
../idl/KalmanFilterService.idl
../idl/RemoveForceSensorLinkOffsetService.idl
)
configure_file(Doxyfile.in ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile)
set(output_dir ${CMAKE_CURRENT_BINARY_DIR}/html)
Expand Down
88 changes: 67 additions & 21 deletions idl/AutoBalancerService.idl
Original file line number Diff line number Diff line change
Expand Up @@ -13,54 +13,100 @@ module OpenHRP
typedef double DblArray3[3];
typedef double DblArray4[4];

// Foot Step
/**
* @struct Footstep
* @brief Foot step for one leg.
*/
struct Footstep
{
DblArray3 pos; // Foot position [m]
DblArray4 rot; // Foot orientation by quaternion (w,x,y,z)
string leg; // Leg name (rleg or lleg)
/// Foot position [m]
DblArray3 pos;
/// Foot orientation by quaternion (w,x,y,z)
DblArray4 rot;
/// Leg name (rleg or lleg)
string leg;
};

/**
* @struct FootstepSequence
* @brief Sequence of foot step.
*/
typedef sequence<Footstep> FootstepSequence;

/**
* @enum SupportLegState
* @brief State of support leg.
*/
enum SupportLegState {
RLEG,
LLEG,
BOTH
};

/**
* @enum OrbitType
* @brief Orbit type of swing foot.
*/
enum OrbitType {
SHUFFLING,
CYCLOID,
RECTANGLE
};

/**
* @struct FootstepParam
* @brief Foot step parameters.
*/
struct FootstepParam
{
Footstep rleg_coords; // Current right foot coords
Footstep lleg_coords; // Current left foot coords
Footstep support_leg_coords; // Support foot coords
Footstep swing_leg_coords; // Swing foot coords, which is interpolation betwee swing_leg_src_coords and swing_leg_dst_coords
Footstep swing_leg_src_coords; // Source coords for swing foot
Footstep swing_leg_dst_coords; // Destination coords for swing foot
Footstep dst_foot_midcoords; // Destination foot midcoords
SupportLegState support_leg; // RLEG or LLEG
SupportLegState support_leg_with_both; // RLEG, LLEG, or BOTH
/// Current right foot coords
Footstep rleg_coords;
/// Current left foot coords
Footstep lleg_coords;
/// Support foot coords
Footstep support_leg_coords;
/// Swing foot coords, which is interpolation betwee swing_leg_src_coords and swing_leg_dst_coords
Footstep swing_leg_coords;
/// Source coords for swing foot
Footstep swing_leg_src_coords;
/// Destination coords for swing foot
Footstep swing_leg_dst_coords;
/// Destination foot midcoords
Footstep dst_foot_midcoords;
/// RLEG or LLEG
SupportLegState support_leg;
/// RLEG, LLEG, or BOTH
SupportLegState support_leg_with_both;
};

typedef sequence<string> StrSequence;

struct GaitGeneratorParam // Parameters for GaitGenerator
/**
* @struct GaitGeneratorParam
* @brief Parameters for GaitGenerator.
*/
struct GaitGeneratorParam
{
double default_step_time; // Step time [s]
double default_step_height; // Step height [m]
double default_double_support_ratio; // Ratio of double support period. Ratio is included in (0, 1). Double support period time is default_double_support_ratio*default_step_time.
sequence<double, 3> stride_parameter; // Stride limitation of x[m], y[m], and theta[deg] for goPos
OrbitType default_orbit_type; // Default OrbitType
/// Step time [s]
double default_step_time;
/// Step height [m]
double default_step_height;
/// Ratio of double support period. Ratio is included in (0, 1). Double support period time is default_double_support_ratio*default_step_time.
double default_double_support_ratio;
/// Stride limitation of x[m], y[m], and theta[deg] for goPos
sequence<double, 3> stride_parameter;
/// Default OrbitType
OrbitType default_orbit_type;
};

struct AutoBalancerParam // Parameters for AutoBalancer
/**
* @struct AutoBalancerParam
* @brief Parameters for AutoBalancer
*/
struct AutoBalancerParam
{
sequence<DblSequence3, 2> default_zmp_offsets; // ZMP offset vectors[m] for rleg and lleg (<-please set by this order)
/// ZMP offset vectors[m] for rleg and lleg (<-please set by this order)
sequence<DblSequence3, 2> default_zmp_offsets;
double move_base_gain;
};

Expand Down
58 changes: 39 additions & 19 deletions idl/ImpedanceControllerService.idl
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**
* @file ImpedanceControllerService.idl
* @brief Services for the impedance interface
* @brief Services for the impedance controller interface
*/
module OpenHRP
{
Expand All @@ -9,25 +9,45 @@ module OpenHRP
{
typedef sequence<double, 3> DblSequence3;

// Impedance Controller Parameters
/**
* @struct impedanceParam
* @brief Impedance controller parameters for one end-effector.
*/
struct impedanceParam {
string name; // Name of end effector.
string base_name; // Name of inverse kinematics root link.
string target_name; // Name of inverse kinematics end effector link.
double M_p; // Position mass [N/(m/s^2)]
double D_p; // Position damper [N/(m/s)]
double K_p; // Position spring [N/m]
double M_r; // Rotation mass [Nm/(rad/s^2)]
double D_r; // Rotation damper [N/(rad/s)]
double K_r; // Rotation spring [N/rad]
DblSequence3 ref_force; // Reference Force [N] (x,y,z).
DblSequence3 force_gain; // Force gain (x,y,z).
DblSequence3 ref_moment; // Reference Moment [Nm] (x,y,z).
DblSequence3 moment_gain; // Moment gain (x,y,z).
double sr_gain; // SR-inverse gain for inverse kinematics.
double avoid_gain; // Avoid joint limit gain for inverse kinematics.
double reference_gain; // Reference joint angles tracking gain for inverse kinematics.
double manipulability_limit; // Manipulability limit for inverse kinematics.
/// Name of end effector.
string name;
/// Name of inverse kinematics root link.
string base_name;
/// Name of inverse kinematics end effector link.
string target_name;
/// Position mass [N/(m/s^2)]
double M_p;
/// Position damper [N/(m/s)]
double D_p;
/// Position spring [N/m]
double K_p;
/// Rotation mass [Nm/(rad/s^2)]
double M_r;
/// Rotation damper [N/(rad/s)]
double D_r;
/// Rotation spring [N/rad]
double K_r;
/// Reference Force [N] (x,y,z).
DblSequence3 ref_force;
/// Force gain (x,y,z).
DblSequence3 force_gain;
/// Reference Moment [Nm] (x,y,z).
DblSequence3 ref_moment;
/// Moment gain (x,y,z).
DblSequence3 moment_gain;
/// SR-inverse gain for inverse kinematics.
double sr_gain;
/// Avoid joint limit gain for inverse kinematics.
double avoid_gain;
/// Reference joint angles tracking gain for inverse kinematics.
double reference_gain;
/// Manipulability limit for inverse kinematics.
double manipulability_limit;
};

/**
Expand Down
6 changes: 5 additions & 1 deletion idl/KalmanFilterService.idl
Original file line number Diff line number Diff line change
@@ -1,11 +1,15 @@
/**
* @file KalmanFilterService.idl
* @brief Services for the robot hardware interface
* @brief Services for the kalman filter interface
*/
module OpenHRP
{
interface KalmanFilterService
{
/**
* @struct KalmanFilterParam
* @brief KalmanFilter Parameters.
*/
struct KalmanFilterParam
{
double Q_angle;
Expand Down
8 changes: 8 additions & 0 deletions idl/RemoveForceSensorLinkOffsetService.idl
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,19 @@ module OpenHRP
{
interface RemoveForceSensorLinkOffsetService
{
/**
* @struct forcemomentOffsetParam
* @brief Parameters for a link mass and center of mass. The link is assumed to be end-effector-side from force-moment sensor.
*/
typedef sequence<double, 3> DblSequence3;
struct forcemomentOffsetParam {
/// Force offset [N].
DblSequence3 force_offset;
/// Moment offset [Nm].
DblSequence3 moment_offset;
/// Link center of mass in sensor frame [m].
DblSequence3 link_offset_centroid;
/// Link msas [kg].
double link_offset_mass;
};

Expand Down
55 changes: 37 additions & 18 deletions idl/StabilizerService.idl
Original file line number Diff line number Diff line change
@@ -1,20 +1,27 @@
/**
* @file StabilizerService.idl
* @brief Services for the robot hardware interface
* @brief Services for the stabilizer interface
*/
module OpenHRP
{
interface StabilizerService
{
typedef double DblArray2[2];

// Stabilizer Parameters
/**
* @struct stParam
* @brief Stabilizer Parameters.
*/
struct stParam {
// for TPCC
DblArray2 k_tpcc_p; // Feedback gain for ZMP tracking error (x,y)
DblArray2 k_tpcc_x; // Feedback gain for COG position tracking error (x,y)
DblArray2 k_brot_p; // Body posture control gain [rad/s] (roll, pitch).
DblArray2 k_brot_tc; // Time constant for body posture control [s] (roll, pitch).
/// Feedback gain for ZMP tracking error (x,y)
DblArray2 k_tpcc_p;
/// Feedback gain for COG position tracking error (x,y)
DblArray2 k_tpcc_x;
/// Body posture control gain [rad/s] (roll, pitch).
DblArray2 k_brot_p;
/// Time constant for body posture control [s] (roll, pitch).
DblArray2 k_brot_tc;
// for RUNST
DblArray2 k_run_b;
DblArray2 d_run_b;
Expand All @@ -25,18 +32,30 @@ module OpenHRP
double d_run_x;
double d_run_y;
// for EEFM ST
DblArray2 eefm_k1; // Feedback gain for COG position tracking error (x,y)
DblArray2 eefm_k2; // Feedback gain for COG velocity tracking error (x,y)
DblArray2 eefm_k3; // Feedback gain for ZMP tracking error (x,y)
DblArray2 eefm_zmp_delay_time_const; // Time constant for stabilizer ZMP delay [s] (x,y)
DblArray2 eefm_ref_zmp_aux; // Auxiliary input for ZMP position [m] (x,y). This is used for delay model identification
double eefm_rot_damping_gain; // Foot rotation damping gain [Nm/(rad/s)].
double eefm_rot_time_const; // Foot rotation damping time constant [s].
double eefm_pos_damping_gain; // Foot position damping gain [N/(m/s)].
double eefm_pos_time_const_support; // Foot position damping time constant for double support phase [s].
double eefm_pos_time_const_swing; // Foot position damping time constant for single support phase [s].
double eefm_pos_transition_time; // Transition time for single=>double support phase gain interpolation [s].
double eefm_leg_inside_margin; // Inside foot margine [m]. Distance between foot end effector position and foot inside edge.
/// Feedback gain for COG position tracking error (x,y)
DblArray2 eefm_k1;
/// Feedback gain for COG velocity tracking error (x,y)
DblArray2 eefm_k2;
/// Feedback gain for ZMP tracking error (x,y)
DblArray2 eefm_k3;
/// Time constant for stabilizer ZMP delay [s] (x,y)
DblArray2 eefm_zmp_delay_time_const;
/// Auxiliary input for ZMP position [m] (x,y). This is used for delay model identification
DblArray2 eefm_ref_zmp_aux;
/// Foot rotation damping gain [Nm/(rad/s)].
double eefm_rot_damping_gain;
/// Foot rotation damping time constant [s].
double eefm_rot_time_const;
/// Foot position damping gain [N/(m/s)].
double eefm_pos_damping_gain;
/// Foot position damping time constant for double support phase [s].
double eefm_pos_time_const_support;
/// Foot position damping time constant for single support phase [s].
double eefm_pos_time_const_swing;
/// Transition time for single=>double support phase gain interpolation [s].
double eefm_pos_transition_time;
/// Inside foot margine [m]. Distance between foot end effector position and foot inside edge.
double eefm_leg_inside_margin;
};

/**
Expand Down
Loading

0 comments on commit 62a5386

Please sign in to comment.