Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
36 changes: 36 additions & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
---
Checks: '-*,
performance-*,
llvm-namespace-comment,
modernize-redundant-void-arg,
modernize-use-nullptr,
modernize-use-default,
modernize-use-override,
modernize-loop-convert,
readability-named-parameter,
readability-redundant-smartptr-get,
readability-redundant-string-cstr,
readability-simplify-boolean-expr,
readability-container-size-empty,
readability-identifier-naming,
'
HeaderFilterRegex: ''
AnalyzeTemporaryDtors: false
CheckOptions:
- key: llvm-namespace-comment.ShortNamespaceLines
value: '10'
- key: llvm-namespace-comment.SpacesBeforeComments
value: '2'
- key: readability-braces-around-statements.ShortStatementLines
value: '2'
# type names
- key: readability-identifier-naming.ClassCase
value: CamelCase
- key: readability-identifier-naming.EnumCase
value: CamelCase
- key: readability-identifier-naming.UnionCase
value: CamelCase
# method names
- key: readability-identifier-naming.MethodCase
value: camelBack
...
54 changes: 13 additions & 41 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -6,55 +6,27 @@ rvm:
- 2.4
python:
- "2.7"
cache: ccache
compiler: gcc

env:
global:
- ROS_DISTRO=melodic
- DOCKER_IMAGE=moveit/moveit:master-source
- SCRIPT=.moveit_ci/travis.sh
- ROS_DISTRO=noetic
- ROS_REPO=ros-testing
- CXXFLAGS="-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls"
- WARNINGS_OK=false
- UPSTREAM_WORKSPACE="https://github.com/ros-planning/moveit_visual_tools
https://github.com/ros-planning/panda_moveit_config"
matrix:
- TEST="clang-format"
- ROS_DISTRO=melodic

before_install: # Use this to prepare the system to install prerequisites or dependencies
# Define some config vars
- export NOKOGIRI_USE_SYSTEM_LIBRARIES=true
- export REPOSITORY_NAME=${PWD##*/}
- echo "Testing branch $TRAVIS_BRANCH of $REPOSITORY_NAME"
- sudo -E sh -c 'echo "deb http://packages.ros.org/ros/ubuntu `lsb_release -cs` 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-rosdep python-wstool python-catkin-tools
# Setup rosdep
- sudo rosdep init
- rosdep update
# Install htmlpoofer
- gem update --system
- gem --version
- gem install html-proofer
# Install ROS's version of sphinx
- sudo apt-get -qq install ros-kinetic-rosdoc-lite
- source /opt/ros/kinetic/setup.bash
- SCRIPT=htmlproofer.sh
- TEST="clang-format catkin_lint"
- TEST="clang-tidy-fix"
- DOCKER_IMAGE=moveit/moveit:master-source ROS_REPO=

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

script:
# Build tutorial examples
- .moveit_ci/travis.sh
# Test build with non-ROS wrapped Sphinx command to allow warnings and errors to be caught
- sphinx-build -W -b html . native_build
# Test build with ROS-version of Sphinx command so that it is generated same as ros.org
- rosdoc_lite -o build .
# Run HTML tests on generated build output to check for 404 errors, etc
- test "$TRAVIS_PULL_REQUEST" == false || URL_SWAP="--url-swap https\://github.com/ros-planning/moveit_tutorials/blob/master/:file\://$PWD/build/html/"
- htmlproofer ./build --only-4xx --check-html --file-ignore ./build/html/genindex.html,./build/html/search.html --alt-ignore '/.*/' --url-ignore '#' $URL_SWAP

# after_success and deploy are skipped if build is broken
after_success:
# Tell GitHub Pages not to bypass Jekyll processing
- touch build/html/.nojekyll
./$SCRIPT

deploy:
# Deploy to gh-pages branch
Expand All @@ -66,5 +38,5 @@ deploy:
# Only copy build output directory to gh-pages
local_dir: build/html
on:
# Source branch
branch: master
condition: $SCRIPT = htmlproofer.sh
6 changes: 4 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,11 @@ find_package(catkin REQUIRED
COMPONENTS
interactive_markers
moveit_core
moveit_visual_tools
moveit_ros_planning
moveit_ros_planning_interface
moveit_ros_perception
rviz_visual_tools
moveit_visual_tools
pluginlib
geometric_shapes
pcl_ros
Expand Down Expand Up @@ -46,7 +47,8 @@ catkin_package(
## Build ##
###########

include_directories(${THIS_PACKAGE_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIR} ${EIGEN3_INCLUDE_DIRS})
include_directories(${THIS_PACKAGE_INCLUDE_DIRS})
include_directories(SYSTEM ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIR} ${EIGEN3_INCLUDE_DIRS})

add_subdirectory(doc/kinematics)
add_subdirectory(doc/robot_model_and_robot_state)
Expand Down
Empty file modified _static/logo.png
100755 → 100644
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class ExampleControllerHandle : public moveit_controller_manager::MoveItControll
{
}

bool sendTrajectory(const moveit_msgs::RobotTrajectory& t) override
bool sendTrajectory(const moveit_msgs::RobotTrajectory& /*t*/) override
{
// do whatever is needed to actually execute this trajectory
return true;
Expand Down Expand Up @@ -134,7 +134,7 @@ class MoveItControllerManagerExample : public moveit_controller_manager::MoveItC
* Controllers are all active and default.
*/
moveit_controller_manager::MoveItControllerManager::ControllerState
getControllerState(const std::string& name) override
getControllerState(const std::string& /*name*/) override
{
moveit_controller_manager::MoveItControllerManager::ControllerState state;
state.active_ = true;
Expand All @@ -143,7 +143,8 @@ class MoveItControllerManagerExample : public moveit_controller_manager::MoveItC
}

/* Cannot switch our controllers */
bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate) override
bool switchControllers(const std::vector<std::string>& /*activate*/,
const std::vector<std::string>& /*deactivate*/) override
{
return false;
}
Expand Down
22 changes: 8 additions & 14 deletions doc/creating_moveit_plugins/lerp_motion_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,29 +1,23 @@
include_directories(include)
include_directories(
include
${catkin_INCLUDE_DIRS}
SYSTEM
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
)

add_library(${PROJECT_NAME}
src/lerp_interface.cpp
src/lerp_planning_context.cpp
)

target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES})
set_target_properties(${PROJECT_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

add_executable(lerp_example src/lerp_example.cpp)
target_link_libraries(lerp_example
${catkin_LIBRARIES}
${Boost_LIBRARIES}
)

# Lerp planning plugin
add_library(moveit_lerp_planner_plugin src/lerp_planner_manager.cpp)
add_library(moveit_lerp_planner_plugin
src/lerp_planner_manager.cpp
src/lerp_interface.cpp
src/lerp_planning_context.cpp)
set_target_properties(moveit_lerp_planner_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

target_link_libraries(moveit_lerp_planner_plugin ${PROJECT_NAME} ${catkin_LIBRARIES})
target_link_libraries(moveit_lerp_planner_plugin ${catkin_LIBRARIES} ${Boost_LIBRARIES})

#############
## Install ##
Expand Down Expand Up @@ -56,6 +50,6 @@ install(
DESTINATION
${CATKIN_PACKAGE_SHARE_DESTINATION}
)

#catkin_lint ignore uninstalled_plugin
install(FILES lerp_interface_plugin_description.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/doc/creating_moveit_plugins/lerp_motion_planner/)
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class LERPInterface
int dof_;

private:
void interpolate(const std::vector<std::string> joint_names, moveit::core::RobotStatePtr& robot_state,
void interpolate(const std::vector<std::string>& joint_names, moveit::core::RobotStatePtr& robot_state,
const moveit::core::JointModelGroup* joint_model_group, const std::vector<double>& start_joint_vals,
const std::vector<double>& goal_joint_vals, trajectory_msgs::JointTrajectory& joint_trajectory);
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,6 @@ int main(int argc, char** argv)

// Create JointModelGroup
const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(PLANNING_GROUP);
const std::vector<std::string>& joint_names = joint_model_group->getActiveJointModelNames();
const std::vector<std::string>& link_model_names = joint_model_group->getLinkModelNames();
ROS_INFO_NAMED(NODE_NAME, "end effector name %s\n", link_model_names.back().c_str());

Expand Down Expand Up @@ -183,9 +182,9 @@ int main(int argc, char** argv)
std::vector<double> solution_positions;
solution_positions = solution_traj.joint_trajectory.points[step_num].positions;
std::stringstream sst;
for (int i = 0; i < solution_positions.size(); ++i)
for (double solution_position : solution_positions)
{
sst << solution_positions[i] << " ";
sst << solution_position << " ";
}
ROS_INFO_STREAM_NAMED(NODE_NAME, sst.str());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,9 @@ bool LERPInterface::solve(const planning_scene::PlanningSceneConstPtr& planning_
std::vector<moveit_msgs::JointConstraint> goal_joint_constraint = goal_constraints[0].joint_constraints;

std::vector<double> goal_joint_values;
for (auto constraint : goal_joint_constraint)
goal_joint_values.reserve(goal_joint_constraint.size());

for (const auto& constraint : goal_joint_constraint)
{
goal_joint_values.push_back(constraint.position);
}
Expand All @@ -102,7 +104,7 @@ bool LERPInterface::solve(const planning_scene::PlanningSceneConstPtr& planning_
return true;
}

void LERPInterface::interpolate(const std::vector<std::string> joint_names, moveit::core::RobotStatePtr& rob_state,
void LERPInterface::interpolate(const std::vector<std::string>& joint_names, moveit::core::RobotStatePtr& rob_state,
const moveit::core::JointModelGroup* joint_model_group,
const std::vector<double>& start_joint_vals, const std::vector<double>& goal_joint_vals,
trajectory_msgs::JointTrajectory& joint_trajectory)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class LERPPlannerManager : public planning_interface::PlannerManager
{
}

bool initialize(const moveit::core::RobotModelConstPtr& model, const std::string& ns) override
bool initialize(const moveit::core::RobotModelConstPtr& model, const std::string& /*ns*/) override
{
for (const std::string& gpName : model->getJointModelGroupNames())
{
Expand Down
12 changes: 7 additions & 5 deletions doc/interactivity/include/interactivity/imarker.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@

#include <interactive_markers/interactive_marker_server.h>
#include <Eigen/Geometry>
#include <utility>

/* Interactive marker.
*
Expand Down Expand Up @@ -69,7 +70,8 @@ class IMarker
Dof dof = BOTH)
: imarker_()
{
initialize(server, name, Eigen::Vector3d(0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0), frame_id, callback, dof);
initialize(server, name, Eigen::Vector3d(0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0), frame_id, std::move(callback),
dof);
}

/** create an interactive marker with an initial pose */
Expand All @@ -82,7 +84,7 @@ class IMarker
Eigen::Quaterniond q(pose.linear());
Eigen::Vector3d p = pose.translation();

initialize(server, name, p, q, frame_id, callback, dof);
initialize(server, name, p, q, frame_id, std::move(callback), dof);
}

/** create an interactive marker with an initial pose */
Expand All @@ -93,7 +95,7 @@ class IMarker
Dof dof = BOTH)
: imarker_()
{
initialize(server, name, position, orientation, frame_id, callback, dof);
initialize(server, name, position, orientation, frame_id, std::move(callback), dof);
}

/** create an interactive marker with an initial position */
Expand All @@ -103,14 +105,14 @@ class IMarker
Dof dof = BOTH)
: imarker_()
{
initialize(server, name, position, Eigen::Quaterniond(1, 0, 0, 0), frame_id, callback, dof);
initialize(server, name, position, Eigen::Quaterniond(1, 0, 0, 0), frame_id, std::move(callback), dof);
}

/** move marker to new pose */
void move(const Eigen::Isometry3d& pose);

/** default callback which just prints new position and orientation */
static void printFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&);
static void printFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& /*feedback*/);

private:
/* called by constructors */
Expand Down
5 changes: 4 additions & 1 deletion doc/interactivity/include/interactivity/interactive_robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/robot_state.h>
#include <moveit_msgs/DisplayRobotState.h>

#include <utility>

#include "imarker.h"

/** Keeps track of the state of the robot and the world.
Expand Down Expand Up @@ -71,7 +74,7 @@ class InteractiveRobot
/** set a callback to call when updates occur */
void setUserCallback(boost::function<void(InteractiveRobot& robot)> callback)
{
user_callback_ = callback;
user_callback_ = std::move(callback);
}

/** access RobotModel */
Expand Down
4 changes: 3 additions & 1 deletion doc/interactivity/src/imarker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@
#include "interactivity/pose_string.h"
#include <tf2_eigen/tf2_eigen.h>

#include <utility>

/* default callback which just prints the current pose */
void IMarker::printFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
{
Expand Down Expand Up @@ -182,6 +184,6 @@ void IMarker::initialize(interactive_markers::InteractiveMarkerServer& server, c

// tell the server to show the marker and listen for changes
server_->insert(imarker_);
server_->setCallback(imarker_.name, callback);
server_->setCallback(imarker_.name, std::move(callback));
server_->applyChanges();
}
23 changes: 9 additions & 14 deletions doc/interactivity/src/interactive_robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,23 +52,18 @@ const ros::Duration InteractiveRobot::min_delay_(0.01);

InteractiveRobot::InteractiveRobot(const std::string& robot_description, const std::string& robot_topic,
const std::string& marker_topic, const std::string& imarker_topic)
: // this node handle is used to create the publishers
nh_()
,
: user_data_(nullptr)
, nh_() // this node handle is used to create the publishers
// create publishers for markers and robot state
robot_state_publisher_(nh_.advertise<moveit_msgs::DisplayRobotState>(robot_topic, 1))
, robot_state_publisher_(nh_.advertise<moveit_msgs::DisplayRobotState>(robot_topic, 1))
, world_state_publisher_(nh_.advertise<visualization_msgs::Marker>(marker_topic, 100))
,
// create an interactive marker server for displaying interactive markers
interactive_marker_server_(imarker_topic)
, imarker_robot_(0)
, imarker_world_(0)
,
, interactive_marker_server_(imarker_topic)
, imarker_robot_(nullptr)
, imarker_world_(nullptr)
// load the robot description
rm_loader_(robot_description)
, group_(0)
, user_data_(0)
, user_callback_(0)
, rm_loader_(robot_description)
, group_(nullptr)
{
// get the RobotModel loaded from urdf and srdf files
robot_model_ = rm_loader_.getModel();
Expand Down Expand Up @@ -209,7 +204,7 @@ void InteractiveRobot::scheduleUpdate()
}

/* callback called when it is time to publish */
void InteractiveRobot::updateCallback(const ros::TimerEvent& e)
void InteractiveRobot::updateCallback(const ros::TimerEvent& /*event*/)
{
ros::Time tbegin = ros::Time::now();
publish_timer_.stop();
Expand Down
Loading