Skip to content

Commit

Permalink
Scenario: new APIs for gazebo's ECM
Browse files Browse the repository at this point in the history
  • Loading branch information
diegoferigo committed Mar 19, 2020
1 parent 87cd5a5 commit 553e9a4
Show file tree
Hide file tree
Showing 29 changed files with 5,046 additions and 57 deletions.
97 changes: 87 additions & 10 deletions cpp/scenario/gazebo/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,20 +1,52 @@
# Copyright (C) 2020 Istituto Italiano di Tecnologia (IIT). All rights reserved.
# This software may be modified and distributed under the terms of the
# GNU Lesser General Public License v2.1 or any later version.
# 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.

# ================
# Extra Components
# ================

set(EXTRA_COMPONENTS_HDRS
# ${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/ECMMutex.h
# ${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/PreUpdateConditionVariable.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/JointPID.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/Constraint.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/ConstraintsData.h
# ${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/Constraint.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/SimulatedTime.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/BasePoseTarget.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/BaseWorldVelocityTarget.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/BaseWorldAccelerationTarget.h
# ${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/InitialWorldSdf.h
# ${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/InitialModelSdf.h
# ${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/ConstraintsData.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/JointEffortLimit.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/JointControlMode.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/WorldVelocityCmd.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/JointPositionReset.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/JointVelocityReset.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/WorldVelocityCmd.h)
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/JointPositionTarget.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/JointVelocityTarget.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/JointAccelerationTarget.h
${CMAKE_CURRENT_SOURCE_DIR}/include/scenario/gazebo/components/JointControllerPeriod.h)

add_library(ExtraComponents INTERFACE)
target_sources(ExtraComponents INTERFACE ${EXTRA_COMPONENTS_HDRS})
Expand All @@ -25,10 +57,47 @@ target_include_directories(ExtraComponents INTERFACE

target_link_libraries(ExtraComponents INTERFACE ignition-gazebo3::core)

if(NOT CMAKE_BUILD_TYPE STREQUAL "PyPI")
set_target_properties(ExtraComponents PROPERTIES
PUBLIC_HEADER "${EXTRA_COMPONENTS_HDRS}")
endif()
set_target_properties(ExtraComponents PROPERTIES
PUBLIC_HEADER "${EXTRA_COMPONENTS_HDRS}")

# ==============
# ScenarioGazebo
# ==============

set(SCENARIO_PUBLIC_HDRS
include/scenario/gazebo/World.h
include/scenario/gazebo/Model.h
include/scenario/gazebo/Joint.h
include/scenario/gazebo/Link.h
include/scenario/gazebo/Log.h
include/scenario/gazebo/utils.h
include/scenario/gazebo/exceptions.h)

add_library(ScenarioGazebo
${SCENARIO_PUBLIC_HDRS}
include/scenario/gazebo/helpers.h
src/World.cpp
src/Model.cpp
src/Joint.cpp
src/Link.cpp
src/utils.cpp
src/helpers.cpp)

target_include_directories(ScenarioGazebo PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:${CMAKE_INSTALL_INCLUDEDIR}>)

target_link_libraries(ScenarioGazebo
PRIVATE
ExtraComponents
ignition-gazebo3::core)

set_target_properties(ScenarioGazebo PROPERTIES
PUBLIC_HEADER "${SCENARIO_PUBLIC_HDRS}")

# ===================
# Install the targets
# ===================

if(NOT CMAKE_BUILD_TYPE STREQUAL "PyPI")
install(
Expand All @@ -39,4 +108,12 @@ if(NOT CMAKE_BUILD_TYPE STREQUAL "PyPI")
ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR}
RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}
PUBLIC_HEADER DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/scenario/gazebo/components)
install(
TARGETS
ScenarioGazebo
EXPORT scenario
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR}
RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}
PUBLIC_HEADER DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/scenario/gazebo)
endif()
185 changes: 185 additions & 0 deletions cpp/scenario/gazebo/include/scenario/gazebo/Joint.h
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
Loading

0 comments on commit 553e9a4

Please sign in to comment.