Skip to content

Commit

Permalink
[squash] update APIs related to joint forces
Browse files Browse the repository at this point in the history
  • Loading branch information
diegoferigo committed Mar 26, 2020
1 parent cb04422 commit 7709620
Show file tree
Hide file tree
Showing 5 changed files with 197 additions and 154 deletions.
16 changes: 9 additions & 7 deletions cpp/scenario/gazebo/include/scenario/gazebo/Joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -100,28 +100,28 @@ class scenario::gazebo::Joint

double controllerPeriod() const;

double maxEffort() const;
bool setMaxEffort(const double maxEffort);

base::PID pid() const;
bool setPID(const base::PID& pid);

// ==================
// Single DOF methods
// ==================

double force(const size_t dof = 0) const;
double maxGeneralizedForce(const size_t dof = 0) const;
bool setMaxGeneralizedForce(const double maxForce, const size_t dof = 0);

double position(const size_t dof = 0) const;
double velocity(const size_t dof = 0) const;

bool setForce(const double force, const size_t dof = 0);
bool setPositionTarget(const double position, const size_t dof = 0);
bool setVelocityTarget(const double velocity, const size_t dof = 0);
bool setAccelerationTarget(const double acceleration, const size_t dof = 0);
bool setGeneralizedForceTarget(const double force, const size_t dof = 0);

double positionTarget(const size_t dof = 0) const;
double velocityTarget(const size_t dof = 0) const;
double accelerationTarget(const size_t dof = 0) const;
double generalizedForceTarget(const size_t dof = 0) const;

bool resetPosition(const double position, const size_t dof = 0);
bool resetVelocity(const double velocity, const size_t dof = 0);
Expand All @@ -133,18 +133,20 @@ class scenario::gazebo::Joint
// Multi DOF methods
// =================

std::vector<double> jointForce() const;
std::vector<double> jointMaxGeneralizedForce() const;
bool setJointMaxGeneralizedForce(const std::vector<double>& maxForce);
std::vector<double> jointPosition() const;
std::vector<double> jointVelocity() const;

bool setJointForce(const std::vector<double>& force);
bool setJointPositionTarget(const std::vector<double>& position);
bool setJointVelocityTarget(const std::vector<double>& velocity);
bool setJointAccelerationTarget(const std::vector<double>& acceleration);
bool setJointGeneralizedForceTarget(const std::vector<double>& force);

std::vector<double> jointPositionTarget() const;
std::vector<double> jointVelocityTarget() const;
std::vector<double> jointAccelerationTarget() const;
std::vector<double> jointGeneralizedForceTarget() const;

bool resetJointPosition(const std::vector<double>& position);
bool resetJointVelocity(const std::vector<double>& velocity);
Expand Down
10 changes: 5 additions & 5 deletions cpp/scenario/gazebo/include/scenario/gazebo/Model.h
Original file line number Diff line number Diff line change
Expand Up @@ -122,8 +122,6 @@ class scenario::gazebo::Model
// Vectorized Methods
// ==================

std::vector<double> jointForces( //
const std::vector<std::string>& jointNames = {}) const;
std::vector<double> jointPositions( //
const std::vector<std::string>& jointNames = {}) const;
std::vector<double> jointVelocities( //
Expand All @@ -141,9 +139,6 @@ class scenario::gazebo::Model
// Vectorized Target Methods
// =========================

bool setJointForces( //
const std::vector<double> forces,
const std::vector<std::string>& jointNames = {});
bool setJointPositionTargets( //
const std::vector<double> positions,
const std::vector<std::string>& jointNames = {});
Expand All @@ -153,6 +148,9 @@ class scenario::gazebo::Model
bool setJointAccelerationTargets( //
const std::vector<double> velocities,
const std::vector<std::string>& jointNames = {});
bool setJointGeneralizedForceTargets( //
const std::vector<double> forces,
const std::vector<std::string>& jointNames = {});

bool resetJointPositions( //
const std::vector<double> positions,
Expand All @@ -167,6 +165,8 @@ class scenario::gazebo::Model
const std::vector<std::string>& jointNames = {}) const;
std::vector<double> jointAccelerationTargets( //
const std::vector<std::string>& jointNames = {}) const;
std::vector<double> jointGeneralizedForceTargets( //
const std::vector<std::string>& jointNames = {}) const;

// =========
// Base Link
Expand Down
Loading

0 comments on commit 7709620

Please sign in to comment.