Skip to content

Commit

Permalink
Update Travis (#16)
Browse files Browse the repository at this point in the history
* make Travis use moveit_ci
* clang-format
* enable catkin_lint check
  • Loading branch information
rhaschke committed Mar 28, 2019
1 parent 42a63e8 commit 0108aed
Show file tree
Hide file tree
Showing 4 changed files with 109 additions and 66 deletions.
66 changes: 66 additions & 0 deletions .clang-format
@@ -0,0 +1,66 @@
---
BasedOnStyle: Google
AccessModifierOffset: -2
ConstructorInitializerIndentWidth: 2
AlignEscapedNewlinesLeft: false
AlignTrailingComments: true
AllowAllParametersOfDeclarationOnNextLine: false
AllowShortIfStatementsOnASingleLine: false
AllowShortLoopsOnASingleLine: false
AllowShortFunctionsOnASingleLine: None
AllowShortLoopsOnASingleLine: false
AlwaysBreakTemplateDeclarations: true
AlwaysBreakBeforeMultilineStrings: false
BreakBeforeBinaryOperators: false
BreakBeforeTernaryOperators: false
BreakConstructorInitializersBeforeComma: true
BinPackParameters: true
ColumnLimit: 120
ConstructorInitializerAllOnOneLineOrOnePerLine: true
DerivePointerBinding: false
PointerBindsToType: true
ExperimentalAutoDetectBinPacking: false
IndentCaseLabels: true
MaxEmptyLinesToKeep: 1
NamespaceIndentation: None
ObjCSpaceBeforeProtocolList: true
PenaltyBreakBeforeFirstCallParameter: 19
PenaltyBreakComment: 60
PenaltyBreakString: 100
PenaltyBreakFirstLessLess: 1000
PenaltyExcessCharacter: 1000
PenaltyReturnTypeOnItsOwnLine: 70
SpacesBeforeTrailingComments: 2
Cpp11BracedListStyle: false
Standard: Auto
IndentWidth: 2
TabWidth: 2
UseTab: Never
IndentFunctionDeclarationAfterType: false
SpacesInParentheses: false
SpacesInAngles: false
SpaceInEmptyParentheses: false
SpacesInCStyleCastParentheses: false
SpaceAfterControlStatementKeyword: true
SpaceBeforeAssignmentOperators: true
ContinuationIndentWidth: 4
SortIncludes: false
SpaceAfterCStyleCast: false

# Configure each individual brace in BraceWrapping
BreakBeforeBraces: Custom

# Control of individual brace wrapping cases
BraceWrapping: {
AfterClass: 'true'
AfterControlStatement: 'true'
AfterEnum : 'true'
AfterFunction : 'true'
AfterNamespace : 'true'
AfterStruct : 'true'
AfterUnion : 'true'
BeforeCatch : 'true'
BeforeElse : 'true'
IndentBraces : 'false'
}
...
51 changes: 16 additions & 35 deletions .travis.yml
@@ -1,6 +1,10 @@
# Generic MoveIt Travis Continuous Integration Configuration File
# Works with all MoveIt! repositories/branches
# Author: Dave Coleman, Jonathan Bohren
sudo: required
dist: trusty
services:
- docker
language:
- cpp
- python
Expand All @@ -14,38 +18,15 @@ notifications:
- dave.hershberger@sri.com
on_success: change #[always|never|change] # default: change
on_failure: change #[always|never|change] # default: always
before_install: # Use this to prepare the system to install prerequisites or dependencies
# Define some config vars
- export ROS_DISTRO=hydro
- export CI_SOURCE_PATH=$(pwd)
- export REPOSITORY_NAME=${PWD##*/}
- echo "Testing branch $TRAVIS_BRANCH of $REPOSITORY_NAME"
- sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu precise main" > /etc/apt/sources.list.d/ros-latest.list'
- wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
- sudo apt-get update -qq
- sudo apt-get install -qq -y python-catkin-pkg python-rosdep python-wstool ros-$ROS_DISTRO-catkin ros-$ROS_DISTRO-ros
# MongoDB hack - I don't fully understand this but its for moveit_warehouse
- sudo apt-get remove -y mongodb mongodb-10gen
- sudo apt-get install -y mongodb-clients mongodb-server -o Dpkg::Options::="--force-confdef" # default actions
# Setup rosdep
- sudo rosdep init
- rosdep update
install: # Use this to install any prerequisites or dependencies necessary to run your build
# Create workspace
- mkdir -p ~/ros/ws_moveit/src
- cd ~/ros/ws_moveit/src
- wstool init .
# Download non-debian stuff
- wstool merge https://raw.github.com/ros-planning/moveit_docs/hydro-devel/moveit.rosinstall
- wstool update
- git clone https://github.com/ros-planning/geometric_shapes.git
# Delete the moveit.rosinstall version of this repo and use the one of the branch we are testing
- rm -rf $REPOSITORY_NAME
- ln -s $CI_SOURCE_PATH . # Link the repo we are testing to the new workspace
- cd ../
# Install dependencies for source repos
- rosdep install --from-paths src --ignore-src --rosdistro $ROS_DISTRO -y
before_script: # Use this to prepare your build for testing e.g. copy database configurations, environment variables, etc.
- source /opt/ros/$ROS_DISTRO/setup.bash
script: # All commands must exit with code 0 on success. Anything else is considered failure.
- catkin_make -j2

env:
matrix:
- ROS_DISTRO=kinetic TEST="catkin_lint clang-format"
- ROS_DISTRO=kinetic ROS_REPO=ros
- ROS_DISTRO=melodic ROS_REPO=ros

before_script:
- git clone -q https://github.com/ros-planning/moveit_ci.git .moveit_ci

script:
- source .moveit_ci/travis.sh
28 changes: 13 additions & 15 deletions include/random_numbers/random_numbers.h
Expand Up @@ -54,19 +54,18 @@ namespace random_numbers
class RandomNumberGenerator
{
public:

/** \brief Constructor. Always sets a "random" random seed */
RandomNumberGenerator(void);

/** \brief Constructor. Allow a seed to be specified for deterministic behaviour */
RandomNumberGenerator(boost::uint32_t seed);

/** \brief Generate a random real between 0 and 1 */
double uniform01(void)
{
return uni_();
}

/**
* @brief Generate a random real within given bounds: [\e lower_bound, \e upper_bound)
* @param lower_bound The lower bound
Expand All @@ -82,39 +81,38 @@ class RandomNumberGenerator
{
return normal_();
}

/** \brief Generate a random real using a normal distribution with given mean and variance */
double gaussian(double mean, double stddev)
{
return normal_() * stddev + mean;
}

/** \brief Uniform random unit quaternion sampling. The computed value has the order (x,y,z,w)
* @param value[4] A four dimensional array in which the computed quaternion will be returned
*/
void quaternion(double value[4]);

/** \brief Generate an integer uniformly at random within a specified range (inclusive) */
int uniformInteger(int min, int max)
{
boost::uniform_int<> dis(min, max);
boost::uniform_int<> dis(min, max);
return dis(generator_);
}

/**
* \brief Allow the randomly generated seed to be saved so that experiments / benchmarks can be recreated in the future
* \brief Allow the randomly generated seed to be saved so that experiments / benchmarks can be recreated in the
* future
*/
boost::uint32_t getFirstSeed();

private:

boost::mt19937 generator_;
boost::uniform_real<> uniDist_;
boost::normal_distribution<> normalDist_;
boost::variate_generator<boost::mt19937&, boost::uniform_real<> > uni_;
boost::mt19937 generator_;
boost::uniform_real<> uniDist_;
boost::normal_distribution<> normalDist_;
boost::variate_generator<boost::mt19937&, boost::uniform_real<> > uni_;
boost::variate_generator<boost::mt19937&, boost::normal_distribution<> > normal_;
};

}

#endif
30 changes: 14 additions & 16 deletions src/random_numbers.cpp
Expand Up @@ -49,9 +49,10 @@ static boost::uint32_t first_seed_ = 0;
static boost::uint32_t firstSeed(void)
{
boost::scoped_ptr<int> mem(new int());
first_seed_ = (boost::uint32_t)((boost::posix_time::microsec_clock::universal_time() -
boost::posix_time::ptime(boost::date_time::min_date_time)).total_microseconds() +
(unsigned long long)(mem.get()));
first_seed_ = (boost::uint32_t)(
(boost::posix_time::microsec_clock::universal_time() - boost::posix_time::ptime(boost::date_time::min_date_time))
.total_microseconds() +
(unsigned long long)(mem.get()));
return first_seed_;
}

Expand All @@ -63,27 +64,23 @@ static boost::uint32_t nextSeed(void)
static boost::mutex rngMutex;
boost::mutex::scoped_lock slock(rngMutex);
static boost::lagged_fibonacci607 sGen(firstSeed());
static boost::uniform_int<> sDist(1, 1000000000);
static boost::uniform_int<> sDist(1, 1000000000);
static boost::variate_generator<boost::lagged_fibonacci607&, boost::uniform_int<> > s(sGen, sDist);
boost::uint32_t v = s();
return v;
}


random_numbers::RandomNumberGenerator::RandomNumberGenerator(void) : generator_(nextSeed()),
uniDist_(0, 1),
normalDist_(0, 1),
uni_(generator_, uniDist_),
normal_(generator_, normalDist_)
random_numbers::RandomNumberGenerator::RandomNumberGenerator(void)
: generator_(nextSeed())
, uniDist_(0, 1)
, normalDist_(0, 1)
, uni_(generator_, uniDist_)
, normal_(generator_, normalDist_)
{
}

random_numbers::RandomNumberGenerator::RandomNumberGenerator(boost::uint32_t seed)
: generator_(seed),
uniDist_(0, 1),
normalDist_(0, 1),
uni_(generator_, uniDist_),
normal_(generator_, normalDist_)
: generator_(seed), uniDist_(0, 1), normalDist_(0, 1), uni_(generator_, uniDist_), normal_(generator_, normalDist_)
{
// Because we manually specified a seed, we need to save it ourselves
first_seed_ = seed;
Expand All @@ -95,7 +92,8 @@ void random_numbers::RandomNumberGenerator::quaternion(double value[4])
{
double x0 = uni_();
double r1 = sqrt(1.0 - x0), r2 = sqrt(x0);
double t1 = 2.0 * boost::math::constants::pi<double>() * uni_(), t2 = 2.0 * boost::math::constants::pi<double>() * uni_();
double t1 = 2.0 * boost::math::constants::pi<double>() * uni_(),
t2 = 2.0 * boost::math::constants::pi<double>() * uni_();
double c1 = cos(t1), s1 = sin(t1);
double c2 = cos(t2), s2 = sin(t2);
value[0] = s1 * r1;
Expand Down

0 comments on commit 0108aed

Please sign in to comment.