Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • gsaurel/hpp-manipulation
  • humanoid-path-planner/hpp-manipulation
2 results
Show changes
Commits on Source (63)
Showing
with 162 additions and 27 deletions
name: "CI - Nix"
on:
push:
jobs:
tests:
name: "Nix build on ${{ matrix.os }}"
runs-on: "${{ matrix.os }}-latest"
strategy:
matrix:
os: [ubuntu]
steps:
- uses: actions/checkout@v4
- uses: cachix/install-nix-action@v27
- uses: cachix/cachix-action@v15
with:
name: gepetto
authToken: '${{ secrets.CACHIX_AUTH_TOKEN }}'
- run: nix build -L
include: http://rainboard.laas.fr/project/hpp-manipulation/.gitlab-ci.yml
include: https://rainboard.laas.fr/project/hpp-manipulation/.gitlab-ci.yml
pull_request_rules:
- name: merge automatically when CI passes and PR is approved
conditions:
- check-success = "gitlab-ci"
- check-success = "Nix build on ubuntu"
- check-success = "pre-commit.ci - pr"
- or:
- author = pre-commit-ci[bot]
- author = dependabot[bot]
actions:
merge:
......@@ -2,7 +2,7 @@ ci:
autoupdate_branch: devel
repos:
- repo: https://github.com/astral-sh/ruff-pre-commit
rev: v0.4.8
rev: v0.8.1
hooks:
- id: ruff
args:
......@@ -14,18 +14,18 @@ repos:
hooks:
- id: cmake-format
- repo: https://github.com/pappasam/toml-sort
rev: v0.23.1
rev: v0.24.2
hooks:
- id: toml-sort-fix
exclude: poetry.lock
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v18.1.6
rev: v19.1.4
hooks:
- id: clang-format
args:
- --style=Google
- repo: https://github.com/pre-commit/pre-commit-hooks
rev: v4.6.0
rev: v5.0.0
hooks:
- id: check-added-large-files
- id: check-ast
......
File moved
Subproject commit 657b07cb721ecbc383d4e76438eb6ec5c421a332
Subproject commit 29c0eb4e659304f44d55a0389e2749812d858659
{
"nodes": {
"flake-parts": {
"inputs": {
"nixpkgs-lib": [
"nixpkgs"
]
},
"locked": {
"lastModified": 1719877454,
"narHash": "sha256-g5N1yyOSsPNiOlFfkuI/wcUjmtah+nxdImJqrSATjOU=",
"owner": "hercules-ci",
"repo": "flake-parts",
"rev": "4e3583423212f9303aa1a6337f8dffb415920e4f",
"type": "github"
},
"original": {
"owner": "hercules-ci",
"repo": "flake-parts",
"type": "github"
}
},
"nixpkgs": {
"locked": {
"lastModified": 1727174734,
"narHash": "sha256-xa3TynMF5vaWonmTOg/Ejc1Fmo0GkQnCaVRVkBc3z2I=",
"owner": "gepetto",
"repo": "nixpkgs",
"rev": "0ad139a0e4372abc12320c8c92ee90e0e5e296e1",
"type": "github"
},
"original": {
"owner": "gepetto",
"repo": "nixpkgs",
"type": "github"
}
},
"root": {
"inputs": {
"flake-parts": "flake-parts",
"nixpkgs": "nixpkgs"
}
}
},
"root": "root",
"version": 7
}
{
description = "Classes for manipulation planning";
inputs = {
nixpkgs.url = "github:gepetto/nixpkgs";
flake-parts = {
url = "github:hercules-ci/flake-parts";
inputs.nixpkgs-lib.follows = "nixpkgs";
};
};
outputs =
inputs:
inputs.flake-parts.lib.mkFlake { inherit inputs; } {
systems = [
"x86_64-linux"
"aarch64-linux"
"aarch64-darwin"
"x86_64-darwin"
];
perSystem =
{ pkgs, self', ... }:
{
devShells.default = pkgs.mkShell { inputsFrom = [ self'.packages.default ]; };
packages = {
default = self'.packages.hpp-manipulation;
hpp-manipulation = pkgs.hpp-manipulation.overrideAttrs (_: {
src = pkgs.lib.fileset.toSource {
root = ./.;
fileset = pkgs.lib.fileset.unions [
./CMakeLists.txt
./doc
./include
./package.xml
./plugins
./src
./tests
];
};
});
};
};
};
}
......@@ -64,7 +64,7 @@ class HPP_MANIPULATION_DLLAPI Device : public pinocchio::HumanoidRobot {
virtual std::ostream& print(std::ostream& os) const;
void setRobotRootPosition(const std::string& robotName,
const Transform3f& positionWRTParentJoint);
const Transform3s& positionWRTParentJoint);
virtual pinocchio::DevicePtr_t clone() const;
......
......@@ -88,7 +88,7 @@ typedef constraints::RelativeTransformationR3xSO3 RelativeTransformationR3xSO3;
typedef constraints::RelativeTransformationPtr_t RelativeTransformationPtr_t;
typedef core::value_type value_type;
typedef core::size_type size_type;
typedef core::Transform3f Transform3f;
typedef core::Transform3s Transform3s;
typedef core::vector_t vector_t;
typedef core::vectorIn_t vectorIn_t;
typedef core::vectorOut_t vectorOut_t;
......
......@@ -54,7 +54,7 @@ struct DrawingAttributes {
}
std::string& operator[](const std::string& K) { return attr[K]; }
DrawingAttributes()
: separator(", "), openSection("["), closeSection("]"), attr(){};
: separator(", "), openSection("["), closeSection("]"), attr() {};
};
struct Tooltip {
......@@ -62,7 +62,7 @@ struct Tooltip {
typedef std::list<std::string> TooltipLineVector;
TooltipLineVector v;
Tooltip() : v(){};
Tooltip() : v() {};
inline std::string toStr() const {
std::stringstream ss;
size_t i = v.size();
......
......@@ -50,7 +50,7 @@ namespace graph {
/// Define common methods of the graph components.
class HPP_MANIPULATION_DLLAPI GraphComponent {
public:
virtual ~GraphComponent(){};
virtual ~GraphComponent() {};
/// Get the component name.
const std::string& name() const;
......
......@@ -41,7 +41,7 @@ namespace graph {
/// be ordered because a configuration can be in several states.
class HPP_MANIPULATION_DLLAPI StateSelector {
public:
virtual ~StateSelector(){};
virtual ~StateSelector() {};
/// Create a new StateSelector.
static StateSelectorPtr_t create(const std::string& name);
......
......@@ -103,7 +103,7 @@ class HPP_MANIPULATION_DLLLOCAL NodeBin : public ::hpp::statistics::Bin {
class HPP_MANIPULATION_DLLLOCAL Histogram {
public:
virtual ~Histogram(){};
virtual ~Histogram() {};
virtual void add(const RoadmapNodePtr_t& node) = 0;
......
......@@ -58,7 +58,7 @@ typedef constraints::ImplicitPtr_t ImplicitPtr_t;
class HPP_MANIPULATION_DLLAPI Handle {
public:
static std::string className;
virtual ~Handle(){};
virtual ~Handle() {};
/// Create constraint corresponding to a gripper grasping this object
/// \param robot the robot that grasps the handle,
......@@ -66,7 +66,7 @@ class HPP_MANIPULATION_DLLAPI Handle {
/// \return the constraint of relative position between the handle and
/// the gripper.
static HandlePtr_t create(const std::string& name,
const Transform3f& localPosition,
const Transform3s& localPosition,
const DeviceWkPtr_t& robot,
const JointPtr_t& joint) {
Handle* ptr = new Handle(name, localPosition, robot, joint);
......@@ -98,10 +98,10 @@ class HPP_MANIPULATION_DLLAPI Handle {
/// \}
/// Get local position in joint frame
const Transform3f& localPosition() const { return localPosition_; }
const Transform3s& localPosition() const { return localPosition_; }
/// Set local position in joint frame
void localPosition(const Transform3f& localPosition) {
void localPosition(const Transform3s& localPosition) {
localPosition_ = localPosition;
}
......@@ -175,7 +175,7 @@ class HPP_MANIPULATION_DLLAPI Handle {
/// \param grasp object containing the grasp information
/// \return the constraint of relative position between the handle and
/// the gripper.
Handle(const std::string& name, const Transform3f& localPosition,
Handle(const std::string& name, const Transform3s& localPosition,
const DeviceWkPtr_t& robot, const JointPtr_t& joint)
: name_(name),
localPosition_(localPosition),
......@@ -192,7 +192,7 @@ class HPP_MANIPULATION_DLLAPI Handle {
private:
std::string name_;
/// Position of the handle in the joint frame.
Transform3f localPosition_;
Transform3s localPosition_;
/// Joint to which the handle is linked.
JointPtr_t joint_;
/// Pointer to the robot
......
......@@ -30,6 +30,7 @@
#include <hpp/manipulation/config.hh>
#include <hpp/manipulation/fwd.hh>
#include <hpp/manipulation/problem.hh>
#include <unordered_map>
namespace hpp {
namespace manipulation {
......@@ -100,7 +101,7 @@ class HPP_MANIPULATION_DLLAPI StatesPathFinder : public core::PathPlanner {
public:
struct OptimizationData;
virtual ~StatesPathFinder(){};
virtual ~StatesPathFinder() {};
static StatesPathFinderPtr_t create(const core::ProblemConstPtr_t& problem);
......
......@@ -31,6 +31,7 @@
#include <hpp/core/path-planner.hh>
#include <hpp/manipulation/fwd.hh>
#include <hpp/manipulation/graph/fwd.hh>
namespace hpp {
namespace manipulation {
......@@ -110,6 +111,11 @@ class HPP_MANIPULATION_DLLAPI TransitionPlanner : public core::PathPlanner {
/// continuity.
PathPtr_t directPath(ConfigurationIn_t q1, ConfigurationIn_t q2,
bool validate, bool& success, std::string& status);
/// Validate a configuration with the path validation of an edge.
/// \param q configuration to validate,
/// \param id index of the edge in the constraint graph.
bool validateConfiguration(ConfigurationIn_t q, std::size_t id,
core::ValidationReportPtr_t& report) const;
/// Optimize path using the selected path optimizers
/// \param path input path
/// \return optimized path
......@@ -156,12 +162,18 @@ class HPP_MANIPULATION_DLLAPI TransitionPlanner : public core::PathPlanner {
void init(TransitionPlannerWkPtr_t weak);
private:
/// Check problem and forward maxIterations and timeout to inner problem.
void checkProblemAndForwardParameters();
/// Get pointer to edge from an id
graph::EdgePtr_t getEdgeOrThrow(std::size_t id) const;
/// Pointer to the problem of the inner planner
core::ProblemPtr_t innerProblem_;
/// Pointer to the inner path planner
PathPlannerPtr_t innerPlanner_;
/// Vector of optimizers to call after solve
std::vector<PathOptimizerPtr_t> pathOptimizers_;
/// Time parameterization instance
core::PathOptimizerPtr_t timeParameterization_;
/// weak pointer to itself
TransitionPlannerWkPtr_t weakPtr_;
}; // class TransitionPlanner
......
<?xml version='1.0'?>
<package format='2'>
<name>hpp-manipulation</name>
<version>5.0.0</version>
<version>6.0.0</version>
<description>Classes for manipulation planning. </description>
<maintainer email='hpp@laas.fr'>Joseph Mirabel</maintainer>
......@@ -26,8 +26,8 @@
<build_depend>urdfdom</build_depend>
<exec_depend>urdfdom</exec_depend>
<build_export_depend>urdfdom</build_export_depend>
<build_depend>hpp-fcl</build_depend>
<exec_depend>hpp-fcl</exec_depend>
<build_export_depend>hpp-fcl</build_export_depend>
<build_depend>coal</build_depend>
<exec_depend>coal</exec_depend>
<build_export_depend>coal</build_export_depend>
<test_depend>romeo_description</test_depend>
</package>
......@@ -14,7 +14,7 @@ dependencies = [
description = "Classes for manipulation planning."
license = "BSD-2-Clause"
name = "hpp-manipulation"
version = "5.0.0"
version = "6.0.0"
[tool.ruff]
extend-exclude = ["cmake"]
......
......@@ -50,7 +50,7 @@ pinocchio::DevicePtr_t Device::clone() const {
return shPtr;
}
void Device::setRobotRootPosition(const std::string& rn, const Transform3f& t) {
void Device::setRobotRootPosition(const std::string& rn, const Transform3s& t) {
FrameIndices_t idxs = robotFrames(rn);
if (idxs.size() == 0)
throw std::invalid_argument("No frame for robot name " + rn);
......@@ -65,7 +65,7 @@ void Device::setRobotRootPosition(const std::string& rn, const Transform3f& t) {
return;
}
Transform3f shift(t * rootFrame.placement.inverse());
Transform3s shift(t * rootFrame.placement.inverse());
// Find all the frames that have the same parent joint.
for (std::size_t i = 1; i < idxs.size(); ++i) {
Frame& frame = m.frames[idxs[i]];
......