-
Notifications
You must be signed in to change notification settings - Fork 26
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
87cd5a5
commit 553e9a4
Showing
29 changed files
with
5,046 additions
and
57 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,185 @@ | ||
/* | ||
* Copyright (C) 2020 Istituto Italiano di Tecnologia (IIT) | ||
* All rights reserved. | ||
* | ||
* This project is dual licensed under LGPL v2.1+ or Apachi License. | ||
* | ||
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * | ||
* | ||
* This software may be modified and distributed under the terms of the | ||
* GNU Lesser General Public License v2.1 or any later version. | ||
* | ||
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * | ||
* | ||
* Licensed under the Apache License, Version 2.0 (the "License"); | ||
* you may not use this file except in compliance with the License. | ||
* You may obtain a copy of the License at | ||
* | ||
* http://www.apache.org/licenses/LICENSE-2.0 | ||
* | ||
* Unless required by applicable law or agreed to in writing, software | ||
* distributed under the License is distributed on an "AS IS" BASIS, | ||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
* See the License for the specific language governing permissions and | ||
* limitations under the License. | ||
*/ | ||
|
||
#ifndef SCENARIO_GAZEBO_JOINT_H | ||
#define SCENARIO_GAZEBO_JOINT_H | ||
|
||
#include <ignition/gazebo/Entity.hh> | ||
#include <ignition/gazebo/EntityComponentManager.hh> | ||
#include <ignition/gazebo/EventManager.hh> | ||
|
||
#include <limits> | ||
#include <memory> | ||
#include <string> | ||
#include <vector> | ||
|
||
namespace scenario { | ||
namespace base { | ||
struct PID; | ||
struct Limit; | ||
enum class JointType | ||
{ | ||
Invalid, | ||
Fixed, | ||
Revolute, | ||
Prismatic, | ||
Ball, | ||
}; | ||
enum class JointControlMode | ||
{ | ||
Idle, | ||
Force, | ||
Velocity, | ||
Position, | ||
PositionInterpolated, | ||
}; | ||
} // namespace base | ||
namespace gazebo { | ||
class Joint; | ||
class Model; | ||
} // namespace gazebo | ||
} // namespace scenario | ||
|
||
class scenario::gazebo::Joint | ||
{ | ||
public: | ||
Joint(); | ||
virtual ~Joint(); | ||
|
||
// ============ | ||
// Gazebo Joint | ||
// ============ | ||
|
||
uint64_t id() const; | ||
bool initialize(const ignition::gazebo::Entity jointEntity, | ||
ignition::gazebo::EntityComponentManager* ecm, | ||
ignition::gazebo::EventManager* eventManager); | ||
bool createECMResources(); | ||
|
||
bool historyOfAppliedJointForcesEnabled() const; | ||
bool enableHistoryOfAppliedJointForces( // | ||
const bool enable, | ||
const size_t maxHistorySize = 100); | ||
std::vector<double> getHistoryOfAppliedJointForces() const; | ||
|
||
// ========== | ||
// Joint Core | ||
// ========== | ||
|
||
size_t dofs() const; | ||
std::string name() const; | ||
base::JointType type() const; | ||
|
||
base::Limit positionLimit() const; | ||
|
||
base::JointControlMode controlMode() const; | ||
bool setControlMode(const base::JointControlMode mode); | ||
|
||
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 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); | ||
|
||
double positionTarget(const size_t dof = 0) const; | ||
double velocityTarget(const size_t dof = 0) const; | ||
double accelerationTarget(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); | ||
bool reset(const double position, // | ||
const double velocity, | ||
const size_t dof = 0); | ||
|
||
// ================= | ||
// Multi DOF methods | ||
// ================= | ||
|
||
std::vector<double> jointForce() const; | ||
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); | ||
|
||
std::vector<double> jointPositionTarget() const; | ||
std::vector<double> jointVelocityTarget() const; | ||
std::vector<double> jointAccelerationTarget() const; | ||
|
||
bool resetJointPosition(const std::vector<double>& position); | ||
bool resetJointVelocity(const std::vector<double>& velocity); | ||
bool resetJoint(const std::vector<double>& position, | ||
const std::vector<double>& velocity); | ||
|
||
private: | ||
class Impl; | ||
std::unique_ptr<Impl> pImpl; | ||
}; | ||
|
||
struct scenario::base::PID | ||
{ | ||
PID() = default; | ||
PID(const double _p, const double _i, const double _d) | ||
: p(_p) | ||
, i(_i) | ||
, d(_d) | ||
{} | ||
|
||
double p = 0; | ||
double i = 0; | ||
double d = 0; | ||
}; | ||
|
||
struct scenario::base::Limit | ||
{ | ||
Limit() = default; | ||
Limit(const double _min, const double _max) | ||
: min(_min) | ||
, max(_max) | ||
{} | ||
|
||
double min = std::numeric_limits<double>::lowest(); | ||
double max = std::numeric_limits<double>::max(); | ||
}; | ||
|
||
#endif // SCENARIO_GAZEBO_JOINT_H |
Oops, something went wrong.