Skip to content

Commit

Permalink
Clang format (moveit#43)
Browse files Browse the repository at this point in the history
* clang formatting

* adding clang-format notes to README

* fixing build warnings
  • Loading branch information
mlautman authored and davetcoleman committed May 15, 2018
1 parent 566963e commit 4fda0f6
Show file tree
Hide file tree
Showing 17 changed files with 125 additions and 57 deletions.
66 changes: 66 additions & 0 deletions .clang-format
Original file line number Diff line number Diff line change
@@ -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: 1
PenaltyBreakFirstLessLess: 1000
PenaltyExcessCharacter: 1000
PenaltyReturnTypeOnItsOwnLine: 90
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'
}
...
4 changes: 4 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,3 +31,7 @@ Then open ``LOCAL_PACKAGE_PATH/build/html/index.html`` in your web browser.
## Deployment

For deploying documentation changes to the web, [Section 3 of rosdoc_lite wiki](http://wiki.ros.org/rosdoc_lite) says that "rosdoc_lite is automatically run for packages in repositories that have rosinstall files listed in the rosdistro repository." This is done about once every 24 hours, [overnight](http://wiki.ros.org/rosdistro/Tutorials/Indexing%20Your%20ROS%20Repository%20for%20Documentation%20Generation).

## Contributing

These tutorials use the same [style guidelines](http://moveit.ros.org/documentation/contributing/code/) as the MoveIt! project. When modifying or adding to these tutorials, it is required that code is auto formatted using [clang-format](http://moveit.ros.org/documentation/contributing/code/).
11 changes: 5 additions & 6 deletions doc/collision_contact/src/collision_contact_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,9 @@ void computeCollisionContactPoints(InteractiveRobot& robot)
// the contact points for something other than displaying them you can
// iterate through **c_res.contacts** which is a std::map of contact points.
// Look at the implementation of getCollisionMarkersFromContacts() in
// `collision_tools.cpp <https://github.com/ros-planning/moveit/blob/kinetic-devel/moveit_core/collision_detection/src/collision_tools.cpp>`_ for how.
// `collision_tools.cpp
// <https://github.com/ros-planning/moveit/blob/kinetic-devel/moveit_core/collision_detection/src/collision_tools.cpp>`_
// for how.
if (c_res.collision)
{
ROS_INFO("COLLIDING contact_point_count=%d", (int)c_res.contact_count);
Expand All @@ -139,10 +141,7 @@ void computeCollisionContactPoints(InteractiveRobot& robot)
visualization_msgs::MarkerArray markers;

/* Get the contact ponts and display them as markers */
collision_detection::getCollisionMarkersFromContacts(markers,
"panda_link0",
c_res.contacts,
color,
collision_detection::getCollisionMarkersFromContacts(markers, "panda_link0", c_res.contacts, color,
ros::Duration(), // remain until deleted
0.01); // radius
publishMarkers(markers);
Expand Down Expand Up @@ -170,7 +169,7 @@ int main(int argc, char** argv)
// ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
// For this tutorial we use an :codedir:`InteractiveRobot <interactivity/src/interactive_robot.cpp>`
// object as a wrapper that combines a robot_model with the cube and an interactive marker. We also
// create a :planning_scene:`PlanningScene` for collision checking. If you haven't already gone through the
// create a :planning_scene:`PlanningScene` for collision checking. If you haven't already gone through the
// `planning scene tutorial <../planning_scene/planning_scene_tutorial.html>`_, you go through that first.
InteractiveRobot robot;
/* Create a PlanningScene */
Expand Down
4 changes: 2 additions & 2 deletions doc/interactivity/include/interactivity/pose_string.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
#include <Eigen/Geometry>
#include <string>

std::string PoseString(const geometry_msgs::Pose &pose);
std::string PoseString(const Eigen::Affine3d &pose);
std::string PoseString(const geometry_msgs::Pose& pose);
std::string PoseString(const Eigen::Affine3d& pose);

#endif // MOVEIT_TUTORIALS_INTERACTIVITY_SRC_POSE_STRING_
5 changes: 1 addition & 4 deletions doc/interactivity/src/attached_body_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,10 +126,7 @@ void userCallback(InteractiveRobot& robot)
color.b = 1.0;
color.a = 0.5;
visualization_msgs::MarkerArray markers;
collision_detection::getCollisionMarkersFromContacts(markers,
"panda_link0",
c_res.contacts,
color,
collision_detection::getCollisionMarkersFromContacts(markers, "panda_link0", c_res.contacts, color,
ros::Duration(), // remain until deleted
0.01); // radius
publishMarkers(markers);
Expand Down
4 changes: 2 additions & 2 deletions doc/interactivity/src/interactivity_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,12 +57,12 @@ void help()
ROS_INFO("#####################################################");
}

void userCallback(InteractiveRobot &robot)
void userCallback(InteractiveRobot& robot)
{
ROS_INFO_STREAM("Robot position: " << PoseString(robot.robotState()->getGlobalLinkTransform("panda_link8")));
}

int main(int argc, char **argv)
int main(int argc, char** argv)
{
ros::init(argc, argv, "interactivity_tutorial");
ros::NodeHandle nh;
Expand Down
4 changes: 2 additions & 2 deletions doc/interactivity/src/pose_string.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
#include <iomanip>

/** return a string describing a pose (position and quaternion) */
std::string PoseString(const geometry_msgs::Pose &pose)
std::string PoseString(const geometry_msgs::Pose& pose)
{
std::stringstream ss;
ss << "p(";
Expand All @@ -65,7 +65,7 @@ std::string PoseString(const geometry_msgs::Pose &pose)
/** return a string describing a pose
* Assumes the pose is a rotation and a translation
*/
std::string PoseString(const Eigen::Affine3d &pose)
std::string PoseString(const Eigen::Affine3d& pose)
{
geometry_msgs::Pose msg;
tf::poseEigenToMsg(pose, msg);
Expand Down
11 changes: 6 additions & 5 deletions doc/kinematic_model/src/kinematic_model_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/robot_state.h>

int main(int argc, char **argv)
int main(int argc, char** argv)
{
ros::init(argc, argv, "kinematic_model_tutorial");
ros::AsyncSpinner spinner(1);
Expand All @@ -65,7 +65,8 @@ int main(int argc, char **argv)
// the robot description on the ROS parameter server and construct a
// :moveit_core:`RobotModel` for us to use.
//
// .. _RobotModelLoader: http://docs.ros.org/kinetic/api/moveit_ros_planning/html/classrobot__model__loader_1_1RobotModelLoader.html
// .. _RobotModelLoader:
// http://docs.ros.org/kinetic/api/moveit_ros_planning/html/classrobot__model__loader_1_1RobotModelLoader.html
robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
ROS_INFO("Model frame: %s", kinematic_model->getModelFrame().c_str());
Expand All @@ -79,9 +80,9 @@ int main(int argc, char **argv)
// robot.
robot_state::RobotStatePtr kinematic_state(new robot_state::RobotState(kinematic_model));
kinematic_state->setToDefaultValues();
const robot_state::JointModelGroup *joint_model_group = kinematic_model->getJointModelGroup("panda_arm");
const robot_state::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup("panda_arm");

const std::vector<std::string> &joint_names = joint_model_group->getVariableNames();
const std::vector<std::string>& joint_names = joint_model_group->getVariableNames();

// Get Joint Values
// ^^^^^^^^^^^^^^^^
Expand Down Expand Up @@ -114,7 +115,7 @@ int main(int argc, char **argv)
// "panda_link8" which is the most distal link in the
// "panda_arm" group of the robot.
kinematic_state->setToRandomPositions(joint_model_group);
const Eigen::Affine3d &end_effector_state = kinematic_state->getGlobalLinkTransform("panda_link8");
const Eigen::Affine3d& end_effector_state = kinematic_state->getGlobalLinkTransform("panda_link8");

/* Print end-effector pose. Remember that this is in the model frame */
ROS_INFO_STREAM("Translation: \n" << end_effector_state.translation() << "\n");
Expand Down
4 changes: 2 additions & 2 deletions doc/kinematics/src/ros_api_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
// Kinematics
#include <moveit_msgs/GetPositionIK.h>

int main(int argc, char **argv)
int main(int argc, char** argv)
{
ros::init(argc, argv, "panda_arm_kinematics");
ros::AsyncSpinner spinner(1);
Expand Down Expand Up @@ -91,7 +91,7 @@ int main(int argc, char **argv)
robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
robot_state::RobotStatePtr kinematic_state(new robot_state::RobotState(kinematic_model));
const robot_state::JointModelGroup *joint_model_group = kinematic_model->getJointModelGroup("panda_arm");
const robot_state::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup("panda_arm");

/* Get the names of the joints in the panda_arm*/
service_request.ik_request.robot_state.joint_state.name = joint_model_group->getJointModelNames();
Expand Down
8 changes: 5 additions & 3 deletions doc/motion_planning_api/src/motion_planning_api_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,8 @@ int main(int argc, char** argv)
// parameter server and construct a :moveit_core:`RobotModel` for us
// to use.
//
// .. _RobotModelLoader: http://docs.ros.org/indigo/api/moveit_ros_planning/html/classrobot__model__loader_1_1RobotModelLoader.html
// .. _RobotModelLoader:
// http://docs.ros.org/indigo/api/moveit_ros_planning/html/classrobot__model__loader_1_1RobotModelLoader.html
robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
robot_model::RobotModelPtr robot_model = robot_model_loader.getModel();

Expand Down Expand Up @@ -139,7 +140,8 @@ int main(int argc, char** argv)
// `kinematic_constraints`_
// package.
//
// .. _kinematic_constraints: http://docs.ros.org/indigo/api/moveit_core/html/namespacekinematic__constraints.html#a88becba14be9ced36fefc7980271e132
// .. _kinematic_constraints:
// http://docs.ros.org/indigo/api/moveit_core/html/namespacekinematic__constraints.html#a88becba14be9ced36fefc7980271e132
req.group_name = "panda_arm";
moveit_msgs::Constraints pose_goal =
kinematic_constraints::constructGoalConstraints("panda_link8", pose, tolerance_pose, tolerance_angle);
Expand Down Expand Up @@ -184,7 +186,7 @@ int main(int argc, char** argv)

// Now, setup a joint space goal
robot_state::RobotState goal_state(robot_model);
std::vector<double> joint_values = {-1.0, 0.7, 0.7, -1.5, -0.7, 2.0, 0.0};
std::vector<double> joint_values = { -1.0, 0.7, 0.7, -1.5, -0.7, 2.0, 0.0 };
goal_state.setJointGroupPositions(joint_model_group, joint_values);
moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group);
req.goal_constraints.clear();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,16 +55,14 @@ int main(int argc, char** argv)
// BEGIN_TUTORIAL
// Start
// ^^^^^
// Setting up to start using a planning pipeline is pretty easy.
// Before we can load the planner, we need two objects, a RobotModel
// and a PlanningScene.
// We will start by instantiating a
// `RobotModelLoader`_
// object, which will look up
// the robot description on the ROS parameter server and construct a
// :moveit_core:`RobotModel` for us to use.
// Setting up to start using a planning pipeline is pretty easy. Before we can load the planner, we need two objects,
// a RobotModel and a PlanningScene.
//
// .. _RobotModelLoader: http://docs.ros.org/indigo/api/moveit_ros_planning/html/classrobot__model__loader_1_1RobotModelLoader.html
// We will start by instantiating a `RobotModelLoader`_ object, which will look up the robot description on the ROS
// parameter server and construct a :moveit_core:`RobotModel` for us to use.
//
// .. _RobotModelLoader:
// http://docs.ros.org/indigo/api/moveit_ros_planning/html/classrobot__model__loader_1_1RobotModelLoader.html
robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
robot_model::RobotModelPtr robot_model = robot_model_loader.getModel();

Expand Down Expand Up @@ -107,7 +105,8 @@ int main(int argc, char** argv)
// `kinematic_constraints`_
// package.
//
// .. _kinematic_constraints: http://docs.ros.org/indigo/api/moveit_core/html/namespacekinematic__constraints.html#a88becba14be9ced36fefc7980271e132
// .. _kinematic_constraints:
// http://docs.ros.org/indigo/api/moveit_core/html/namespacekinematic__constraints.html#a88becba14be9ced36fefc7980271e132
req.group_name = "panda_arm";
moveit_msgs::Constraints pose_goal =
kinematic_constraints::constructGoalConstraints("panda_link8", pose, tolerance_pose, tolerance_angle);
Expand Down Expand Up @@ -149,7 +148,7 @@ int main(int argc, char** argv)

// Now, setup a joint space goal
robot_state::RobotState goal_state(robot_model);
std::vector<double> joint_values = {-1.0, 0.7, 0.7, -1.5, -0.7, 2.0, 0.0};
std::vector<double> joint_values = { -1.0, 0.7, 0.7, -1.5, -0.7, 2.0, 0.0 };
goal_state.setJointGroupPositions(joint_model_group, joint_values);
moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@

#include <moveit_visual_tools/moveit_visual_tools.h>

int main(int argc, char **argv)
int main(int argc, char** argv)
{
ros::init(argc, argv, "move_group_interface_tutorial");
ros::NodeHandle node_handle;
Expand All @@ -71,8 +71,8 @@ int main(int argc, char **argv)
moveit::planning_interface::PlanningSceneInterface planning_scene_interface;

// Raw pointers are frequently used to refer to the planning group for improved performance.
const robot_state::JointModelGroup *joint_model_group =
move_group.getCurrentState()->getJointModelGroup(PLANNING_GROUP);
const robot_state::JointModelGroup* joint_model_group =
move_group.getCurrentState()->getJointModelGroup(PLANNING_GROUP);

// Visualization
// ^^^^^^^^^^^^^
Expand Down Expand Up @@ -301,7 +301,7 @@ int main(int argc, char **argv)
primitive.dimensions[1] = 0.1;
primitive.dimensions[2] = 0.4;

//Define a pose for the box (specified relative to frame_id)
// Define a pose for the box (specified relative to frame_id)
geometry_msgs::Pose box_pose;
box_pose.orientation.w = 1.0;
box_pose.position.x = 0.4;
Expand Down
12 changes: 6 additions & 6 deletions doc/pick_place/src/pick_place_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@

static const std::string ROBOT_DESCRIPTION = "robot_description";

void openGripper(trajectory_msgs::JointTrajectory &posture)
void openGripper(trajectory_msgs::JointTrajectory& posture)
{
posture.joint_names.resize(6);
posture.joint_names[0] = "r_gripper_joint";
Expand All @@ -63,7 +63,7 @@ void openGripper(trajectory_msgs::JointTrajectory &posture)
posture.points[0].positions[5] = 0.477;
}

void closedGripper(trajectory_msgs::JointTrajectory &posture)
void closedGripper(trajectory_msgs::JointTrajectory& posture)
{
posture.joint_names.resize(6);
posture.joint_names[0] = "r_gripper_joint";
Expand All @@ -83,7 +83,7 @@ void closedGripper(trajectory_msgs::JointTrajectory &posture)
posture.points[0].positions[5] = 0.002;
}

void pick(moveit::planning_interface::MoveGroupInterface &group)
void pick(moveit::planning_interface::MoveGroupInterface& group)
{
std::vector<moveit_msgs::Grasp> grasps;

Expand Down Expand Up @@ -118,7 +118,7 @@ void pick(moveit::planning_interface::MoveGroupInterface &group)
group.pick("part", grasps);
}

void place(moveit::planning_interface::MoveGroupInterface &group)
void place(moveit::planning_interface::MoveGroupInterface& group)
{
std::vector<moveit_msgs::PlaceLocation> loc;

Expand Down Expand Up @@ -151,7 +151,7 @@ void place(moveit::planning_interface::MoveGroupInterface &group)
// add path constraints
moveit_msgs::Constraints constr;
constr.orientation_constraints.resize(1);
moveit_msgs::OrientationConstraint &ocm = constr.orientation_constraints[0];
moveit_msgs::OrientationConstraint& ocm = constr.orientation_constraints[0];
ocm.link_name = "r_wrist_roll_link";
ocm.header.frame_id = p.header.frame_id;
ocm.orientation.x = 0.0;
Expand All @@ -168,7 +168,7 @@ void place(moveit::planning_interface::MoveGroupInterface &group)
group.place("part", loc);
}

int main(int argc, char **argv)
int main(int argc, char** argv)
{
ros::init(argc, argv, "panda_arm_pick_place");
ros::AsyncSpinner spinner(1);
Expand Down
2 changes: 1 addition & 1 deletion doc/planning/src/move_group_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@
#include <moveit/robot_state/robot_state.h>
#include <moveit/robot_state/conversions.h>

int main(int argc, char **argv)
int main(int argc, char** argv)
{
ros::init(argc, argv, "move_group_tutorial");
ros::AsyncSpinner spinner(1);
Expand Down
Loading

0 comments on commit 4fda0f6

Please sign in to comment.