Unverified Commit 3a7d0382 authored by olivier stasse's avatar olivier stasse Committed by GitHub
Browse files

Merge pull request #5 from olivier-stasse/master

Change headers to UTF8 and fix problem with >>
parents 1de611c4 94568a81
Pipeline #1296 failed with stage
in 0 seconds
[submodule "cmake"]
path = cmake
url = https://github.com/jrl-umi3218/jrl-cmakemodules.git
[submodule ".travis"]
path = .travis
url = https://github.com/jrl-umi3218/jrl-travis.git
Subproject commit bad6dbd29cf70e852e5e427e876390d954ca7d6b
language: generic
python:
- "2.7"
sudo: required
dist: trusty
compiler:
- gcc
# - clang
env:
global:
- secure: "SnIBG/xLIHX3CSvUbqqsX8xTVqIqQ7fFS6HWO6KZQVBsT6yugTwYHbyhNiU531JejYJ/I3ZrDhXfYH3qFZiYxnH1sifvwV+fnTtMXpPN7qPZwIymkjcmm6gJF51e0C7VOfUbvKFv0ngwj+ul21rgZSMuoEvxPK0WxtE3/ZSfn9c="
- APT_DEPENDENCIES="doxygen libeigen3-dev "
- DEBSIGN_KEYID=5AE5CD75
- LCOV_IGNORE_RULES="*unittest* /opt/openrobots/*"
- CC=gcc
- DO_COVERAGE_ON_BRANCH="master;release"
- DO_CPPCHECK_ON_BRANCH=""
- DO_INSTALL_DOC_EXCEPT_ON_BRANCH=""
matrix:
# - BUILDTYPE=Release
- BUILDTYPE=Debug
notifications:
email:
- hpp@laas.fr
branches:
only:
- master
- debian
- devel
matrix:
allow_failures:
- compiler:
before_install: ./travis_custom/custom_before_install
install:
- pip install --user coveralls
- pip install --user numpy
script:
- export CMAKE_ADDITIONAL_OPTIONS="-DCMAKE_BUILD_TYPE=${BUILDTYPE}"
- sudo free -m -t
- ./.travis/run ../travis_custom/custom_build
after_failure: ./.travis/run after_failure
after_success:
- ./.travis/run after_success
Subproject commit 7b0b47cae2b082521ad674c8ee575f594f483cd7
Subproject commit 8474524906099169b05f5c2d0523519d8e383df1
......@@ -19,7 +19,7 @@ namespace parametriccurves
/// The sinusoid is actually a cosine so that it starts with zero velocity.
/// Returns x = x_init + A*cos(2*pi*f*t) where f is give by 1/(2*traj_time)
template<typename Numeric=double, std::size_t Dim=1,
typename Point= Eigen::Matrix<Numeric, Dim, 1>>
typename Point= Eigen::Matrix<Numeric, Dim, 1> >
struct Constant :
public AbstractCurve<Numeric, Point>
{
......
......@@ -20,7 +20,7 @@ namespace parametriccurves
/// s = s_0 + u_0*t+0.5*a_0*t^2
template<typename Numeric=double, std::size_t Dim=1,
typename Point= Eigen::Matrix<Numeric, Dim, 1>>
typename Point= Eigen::Matrix<Numeric, Dim, 1> >
struct InfiniteConstAcc :
public AbstractCurve<Numeric, Point>
{
......
......@@ -19,7 +19,7 @@ namespace parametriccurves
/// The sinusoid is actually a cosine so that it starts with zero velocity.
/// Returns x = x_init + A*cos(2*pi*f*t) where f is give by 1/(2*traj_time)
template<typename Numeric=double, std::size_t Dim=1,
typename Point= Eigen::Matrix<Numeric, Dim, 1>>
typename Point= Eigen::Matrix<Numeric, Dim, 1> >
struct InfiniteSinusoid :
public AbstractCurve<Numeric, Point>
{
......
......@@ -22,7 +22,7 @@ namespace parametriccurves
* up to a value f1. Then it goes back to f0 and the trajectory is ended.
*/
template<typename Numeric=double, std::size_t Dim=1,
typename Point= Eigen::Matrix<Numeric, Dim, 1>>
typename Point= Eigen::Matrix<Numeric, Dim, 1> >
struct LinearChirp :
public AbstractCurve<Numeric, Point>
{
......
......@@ -18,7 +18,7 @@ namespace parametriccurves
* \brief Creates MinimumJerk curve
*/
template<typename Numeric=double, std::size_t Dim=1,
typename Point= Eigen::Matrix<Numeric, Dim, 1>>
typename Point= Eigen::Matrix<Numeric, Dim, 1> >
struct MinimumJerk :
public AbstractCurve<Numeric, Point>
{
......
......@@ -16,7 +16,7 @@ namespace parametriccurves
/// \class TextFile.
/// \brief Loads curve from file
template<typename Numeric=double, std::size_t Dim=Eigen::Dynamic,
typename Point= Eigen::Matrix<Numeric, Dim, 1>>
typename Point= Eigen::Matrix<Numeric, Dim, 1> >
struct TextFile :
public AbstractCurve<Numeric, Point>
{
......
......@@ -36,11 +36,14 @@ SET(PYTHON_FILES
FOREACH(python ${PYTHON_FILES})
GET_FILENAME_COMPONENT(pythonFile ${python} NAME)
EXECUTE_PROCESS(COMMAND ${CMAKE_COMMAND} -E ${LINK}
${${PROJECT_NAME}_SOURCE_DIR}/python/${python}
${CMAKE_BINARY_DIR}/bindings/python/${PROJECT_NAME}/${pythonFile})
# Generate pyc file
EXECUTE_PROCESS(COMMAND
add_custom_target(${pythonFile}c ALL
COMMAND
${CMAKE_COMMAND} -E ${LINK}
${${PROJECT_NAME}_SOURCE_DIR}/python/${python}
${CMAKE_BINARY_DIR}/bindings/python/${PROJECT_NAME}/${pythonFile}
COMMAND
${PYTHON_EXECUTABLE} -m py_compile
${CMAKE_BINARY_DIR}/bindings/python/${PROJECT_NAME}/${pythonFile})
# Tag pyc file as generated.
......
#include "parametric-curves/spline.hpp"
#include "parametric-curves/polynomial.hpp"
/*#include "parametric-curves/bezier_curve.h"
#include "parametric-curves/spline_deriv_constraint.h"
#include "parametric-curves/helpers/effector_spline.h"
#include "parametric-curves/helpers/effector_spline_rotation.h"
*/
#ifdef EXTENDED
#include "parametric-curves/bezier_curve.h"
#include "parametric-curves/spline_deriv_constraint.h"
#include "parametric-curves/helpers/effector_spline.h"
#include "parametric-curves/helpers/effector_spline_rotation.h"
#endif
#include <string>
#include <iostream>
#include <cmath>
......@@ -17,9 +18,10 @@ namespace parametriccurves
typedef std::vector<point_t,Eigen::aligned_allocator<point_t> > t_point_t;
typedef Polynomial <double, 3, point_t> polynom_t;
typedef Spline <double, 3, point_t> Spline_t;
/*typedef spline_deriv_constraint <double, double, 3, true, point_t> spline_deriv_constraint_t;
#ifdef TEST_EXTENDED
typedef spline_deriv_constraint <double, double, 3, true, point_t> spline_deriv_constraint_t;
typedef bezier_curve <double, double, 3, true, point_t> bezier_curve_t;
*/
#endif
typedef Spline_t::spline_constraints spline_constraints_t;
typedef std::pair<double, point_t> Waypoint;
typedef std::vector<Waypoint> T_Waypoint;
......@@ -137,10 +139,10 @@ void CubicFunctionTest(bool& error)
}
}
#ifdef TEST_EXTENDED
/*bezier_curve Function tests*/
/*
void BezierCurveTest(bool& error)
{
void BezierCurveTest(bool& error)
{
std::string errMsg("In test BezierCurveTest ; unexpected result for x ");
point_t a(1,2,3);
point_t b(2,3,4);
......@@ -226,11 +228,11 @@ void CubicFunctionTest(bool& error)
error = true;
std::cout << "Evaluation of exactCubic error, MinBound should be equal to 1\n";
}
}
}
#include <ctime>
void BezierCurveTestCompareHornerAndBernstein(bool& error)
{
#include <ctime>
void BezierCurveTestCompareHornerAndBernstein(bool& error)
{
using namespace std;
std::vector<double> values;
for (int i =0; i < 100000; ++i)
......@@ -322,10 +324,10 @@ void CubicFunctionTest(bool& error)
std::cout << "time for bernstein eval " << double(e1 - s1) / CLOCKS_PER_SEC << std::endl;
std::cout << "time for horner eval " << double(e2 - s2) / CLOCKS_PER_SEC << std::endl;
}
}
void BezierDerivativeCurveTest(bool& error)
{
void BezierDerivativeCurveTest(bool& error)
{
std::string errMsg("In test BezierDerivativeCurveTest ; unexpected result for x ");
point_t a(1,2,3);
point_t b(2,3,4);
......@@ -341,10 +343,10 @@ void CubicFunctionTest(bool& error)
ComparePoints(cf3(0), cf3.derivate(0.,0), errMsg, error);
ComparePoints(cf3(0), cf3.derivate(0.,1), errMsg, error, true);
ComparePoints(point_t::Zero(), cf3.derivate(0.,100), errMsg, error);
}
}
void BezierDerivativeCurveConstraintTest(bool& error)
{
void BezierDerivativeCurveConstraintTest(bool& error)
{
std::string errMsg("In test BezierDerivativeCurveConstraintTest ; unexpected result for x ");
point_t a(1,2,3);
point_t b(2,3,4);
......@@ -373,9 +375,9 @@ void CubicFunctionTest(bool& error)
ComparePoints(constraints.init_acc, cf3.derivate(0.,2), errMsg, error);
ComparePoints(constraints.end_vel, cf3.derivate(1.,1), errMsg, error);
ComparePoints(constraints.end_acc, cf3.derivate(1.,2), errMsg, error);
}
}
*/
#endif
/*Exact Cubic Function tests*/
void ExactCubicNoErrorTest(bool& error)
{
......@@ -547,8 +549,8 @@ void CheckPointOnline(const std::string& errmsg, const point_t& A, const point_t
}
}
/*
void EffectorTrajectoryTest(bool& error)
{
void EffectorTrajectoryTest(bool& error)
{
// create arbitrary trajectory
T_Waypoint waypoints;
for(double i = 0; i <= 10; i = i + 2)
......@@ -589,23 +591,23 @@ void EffectorTrajectoryTest(bool& error)
CheckPointOnline(errmsg3,(*eff_traj)(9.5),(*eff_traj)(10),i,eff_traj,error);
}
delete eff_traj;
}
}
helpers::quat_t GetXRotQuat(const double theta)
{
helpers::quat_t GetXRotQuat(const double theta)
{
Eigen::AngleAxisd m (theta, Eigen::Vector3d::UnitX());
return helpers::quat_t(Eigen::Quaterniond(m).coeffs().data());
}
}
double GetXRotFromQuat(helpers::quat_ref_const_t q)
{
double GetXRotFromQuat(helpers::quat_ref_const_t q)
{
Eigen::Quaterniond quat (q.data());
Eigen::AngleAxisd m (quat);
return m.angle() / M_PI * 180.;
}
}
void EffectorSplineRotationNoRotationTest(bool& error)
{
void EffectorSplineRotationNoRotationTest(bool& error)
{
// create arbitrary trajectory
T_Waypoint waypoints;
for(double i = 0; i <= 10; i = i + 2)
......@@ -624,10 +626,10 @@ void EffectorSplineRotationNoRotationTest(bool& error)
ComparePoints(q_land , eff_traj(9.98), errmsg,error);
ComparePoints(q_mod , eff_traj(6), errmsg,error);
ComparePoints(q_end , eff_traj(10), errmsg,error);
}
}
void EffectorSplineRotationRotationTest(bool& error)
{
void EffectorSplineRotationRotationTest(bool& error)
{
// create arbitrary trajectory
T_Waypoint waypoints;
for(double i = 0; i <= 10; i = i + 2)
......@@ -647,10 +649,10 @@ void EffectorSplineRotationRotationTest(bool& error)
ComparePoints(q_land, eff_traj(9.98), errmsg,error);
ComparePoints(q_mod , eff_traj(5).tail<4>(), errmsg,error);
ComparePoints(q_end , eff_traj(10), errmsg,error);
}
}
void EffectorSplineRotationWayPointRotationTest(bool& error)
{
void EffectorSplineRotationWayPointRotationTest(bool& error)
{
// create arbitrary trajectory
T_Waypoint waypoints;
for(double i = 0; i <= 10; i = i + 2)
......@@ -683,10 +685,10 @@ void EffectorSplineRotationWayPointRotationTest(bool& error)
ComparePoints(q_land, eff_traj(9.98), errmsg,error);
ComparePoints(q_mod , eff_traj(6), errmsg,error);
ComparePoints(q_end , eff_traj(10), errmsg,error);
}
}
void TestReparametrization(bool& error)
{
void TestReparametrization(bool& error)
{
helpers::rotation_spline s;
const helpers::spline_deriv_constraint_one_dim& sp = s.time_reparam_;
if(sp.min() != 0)
......@@ -717,7 +719,7 @@ void TestReparametrization(bool& error)
error = true;
}
}
}
}
*/
int main(int /*argc*/, char** /*argv[]*/)
{
......
#!/bin/bash
set -e
# Set debug mode
set -x
set -v
# Add robotpkg
sudo sh -c "echo \"deb [arch=amd64] http://robotpkg.openrobots.org/packages/debian/pub trusty robotpkg\" >> /etc/apt/sources.list "
curl http://robotpkg.openrobots.org/packages/debian/robotpkg.key | sudo apt-key add -
# show memory usage before install
sudo free -m -t
# Setup environment variables.
export APT_DEPENDENCIES="doxygen libboost-serialization-dev libeigen3-dev "
# Add Python dependency
export APT_DEPENDENCIES=$APT_DEPENDENCIES" libboost-python-dev robotpkg-eigenpy python2.7-dev python-numpy"
# When this script is called the current directory is ./custom_travis
. ./.travis/run ../.travis/before_install
# End debug mode
set +v
set +x
#!/bin/bash
set -e
# Set debug mode
set -x
set -v
# Setup environment variables.
export CMAKE_ADDITIONAL_OPTIONS=" ${CMAKE_ADDITIONAL_OPTIONS} -DCMAKE_CXX_FLAGS=-DBOOST_SYSTEM_NO_DEPRECATED "
if [[ ";${DO_INSTALL_DOC_EXCEPT_ON_BRANCH};" == *";${CI_BRANCH};"* ]]; then
export CMAKE_ADDITIONAL_OPTIONS=" ${CMAKE_ADDITIONAL_OPTIONS} -DINSTALL_DOCUMENTATION=\"OFF\""
else
export CMAKE_ADDITIONAL_OPTIONS=" ${CMAKE_ADDITIONAL_OPTIONS} -DINSTALL_DOCUMENTATION=\"ON\""
fi
export PKG_CONFIG_PATH="${PKG_CONFIG_PATH}:/opt/openrobots/lib/pkgconfig"
export LD_LIBRARY_PATH="${LD_LIBRARY_PATH}:/opt/openrobots/lib"
# Setup environment variables.
. ./.travis/run ../.travis/build
# End debug mode
set +v
set +x
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment