Skip to content

Commit 05fa7b9

Browse files
author
Emiliano Borghi
committed
Fix Linting
1 parent 292d43f commit 05fa7b9

39 files changed

+810
-725
lines changed

Diff for: .travis.yml

+4-3
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ install:
2222
- sudo rosdep init
2323
- rosdep update
2424
# Use rosdep to install all dependencies (including ROS itself)
25-
- git clone https://github.com/RoboticaUtnFrba/i2c_imu.git $TRAVIS_BUILD_DIR/i2c_imu
25+
# - git clone https://github.com/RoboticaUtnFrba/i2c_imu.git $TRAVIS_BUILD_DIR/i2c_imu
2626
- git clone https://github.com/RoboticaUtnFrba/libcreate.git $TRAVIS_BUILD_DIR/libcreate
2727
- rosdep install --from-paths ./ -i -y --rosdistro $CI_ROS_DISTRO
2828
# Install and compile RTIMULib2
@@ -49,5 +49,6 @@ script:
4949
# Run tests
5050
- catkin_make run_tests && catkin_test_results
5151
# Lint package files
52-
# - sudo apt-get install python-catkin-lint
53-
# - catkin lint -W2 --strict --explain src
52+
- sudo apt-get install python-catkin-lint
53+
- catkin lint -W2 --strict --explain src/create_autonomy --ignore plugin_missing_install --ignore missing_depend --ignore target_name_collision
54+
- catkin_make roslint

Diff for: ca_bringup/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<package format="2">
33
<name>ca_bringup</name>
44
<version>0.0.0</version>
5-
<description>The ca_bringup package</description>
5+
<description>ca_bringup spawns the nodes that the real robot uses</description>
66

77
<maintainer email="[email protected]">Emiliano Borghi</maintainer>
88

Diff for: ca_bumper2pc/CMakeLists.txt

+17-8
Original file line numberDiff line numberDiff line change
@@ -1,26 +1,32 @@
11
cmake_minimum_required(VERSION 2.8.3)
22
project(ca_bumper2pc)
33
find_package(catkin REQUIRED COMPONENTS
4-
roscpp
4+
ca_msgs
55
nodelet
66
pluginlib
7-
ca_msgs
7+
roscpp
8+
roslint
89
sensor_msgs
910
)
1011

1112
catkin_package(
1213
INCLUDE_DIRS include
13-
LIBRARIES ca_bumper2pc_nodelet
14-
CATKIN_DEPENDS roscpp nodelet pluginlib sensor_msgs ca_msgs
14+
LIBRARIES ${PROJECT_NAME}_nodelet
15+
CATKIN_DEPENDS
16+
ca_msgs
17+
nodelet
18+
pluginlib
19+
roscpp
20+
sensor_msgs
1521
)
1622

1723
include_directories(include ${catkin_INCLUDE_DIRS})
1824

19-
add_library(ca_bumper2pc_nodelet src/ca_bumper2pc.cpp)
20-
add_dependencies(ca_bumper2pc_nodelet ${catkin_EXPORTED_TARGETS})
21-
target_link_libraries(ca_bumper2pc_nodelet ${catkin_LIBRARIES})
25+
add_library(${PROJECT_NAME}_nodelet src/${PROJECT_NAME}.cpp)
26+
add_dependencies(${PROJECT_NAME}_nodelet ${catkin_EXPORTED_TARGETS})
27+
target_link_libraries(${PROJECT_NAME}_nodelet ${catkin_LIBRARIES})
2228

23-
install(TARGETS ca_bumper2pc_nodelet
29+
install(TARGETS ${PROJECT_NAME}_nodelet
2430
DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
2531
)
2632
install(DIRECTORY include/${PROJECT_NAME}/
@@ -32,3 +38,6 @@ install(DIRECTORY plugins
3238
install(DIRECTORY launch
3339
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
3440
)
41+
42+
set(ROSLINT_CPP_OPTS "--filter=-build/c++11")
43+
roslint_cpp()

Diff for: ca_bumper2pc/include/ca_bumper2pc/ca_bumper2pc.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -68,9 +68,9 @@ class Bumper2PcNodelet : public nodelet::Nodelet
6868
{
6969
public:
7070
Bumper2PcNodelet()
71-
: P_INF_X(+100*sin(0.34906585)),
72-
P_INF_Y(+100*cos(0.34906585)),
73-
N_INF_Y(-100*cos(0.34906585)),
71+
: P_INF_X(+100 * sin(0.34906585)),
72+
P_INF_Y(+100 * cos(0.34906585)),
73+
N_INF_Y(-100 * cos(0.34906585)),
7474
ZERO(0), prev_bumper(0), prev_cliff(0) { }
7575
~Bumper2PcNodelet() { }
7676

@@ -94,7 +94,7 @@ class Bumper2PcNodelet : public nodelet::Nodelet
9494
ros::Publisher pointcloud_pub_;
9595
ros::Subscriber cliff_event_subscriber_ ;
9696
ros::Subscriber bumper_event_subscriber_;
97-
97+
9898
sensor_msgs::PointCloud2 pointcloud_;
9999

100100
/**
@@ -105,6 +105,6 @@ class Bumper2PcNodelet : public nodelet::Nodelet
105105
void cliffSensorCB(const ca_msgs::Cliff::ConstPtr& msg_cliff);
106106
};
107107

108-
} // namespace create_bumper2pc
108+
} // namespace create_bumper2pc
109109

110110
#endif // _CA_BUMPER2PC_HPP_

Diff for: ca_bumper2pc/package.xml

+5-4
Original file line numberDiff line numberDiff line change
@@ -15,16 +15,17 @@
1515

1616
<buildtool_depend>catkin</buildtool_depend>
1717

18-
<build_depend>roscpp</build_depend>
18+
<build_depend>ca_msgs</build_depend>
1919
<build_depend>nodelet</build_depend>
2020
<build_depend>pluginlib</build_depend>
21-
<build_depend>ca_msgs</build_depend>
21+
<build_depend>roscpp</build_depend>
22+
<build_depend>roslint</build_depend>
2223
<build_depend>sensor_msgs</build_depend>
2324

24-
<run_depend>roscpp</run_depend>
25+
<run_depend>ca_msgs</run_depend>
2526
<run_depend>nodelet</run_depend>
2627
<run_depend>pluginlib</run_depend>
27-
<run_depend>ca_msgs</run_depend>
28+
<run_depend>roscpp</run_depend>
2829
<run_depend>sensor_msgs</run_depend>
2930

3031
<export>

Diff for: ca_bumper2pc/src/ca_bumper2pc.cpp

+30-18
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
*
44
* @brief Bumper to pointcloud nodelet class implementation.
55
*
6-
*
6+
* Copyright 2020
77
*
88
**/
99

@@ -15,6 +15,8 @@
1515

1616
#include "ca_bumper2pc/ca_bumper2pc.hpp"
1717

18+
#include <string>
19+
1820
namespace create_bumper2pc
1921
{
2022

@@ -23,13 +25,14 @@ void Bumper2PcNodelet::bumperSensorCB(const ca_msgs::Bumper::ConstPtr& msg_bump)
2325
if (pointcloud_pub_.getNumSubscribers() == 0)
2426
return;
2527

26-
// We publish just one "no events" pc (with all three points far away) and stop spamming when bumper/cliff conditions disappear
27-
if (! (msg_bump->is_left_pressed || msg_bump->is_right_pressed) && ! prev_bumper)
28+
// We publish just one "no events" pc (with all three points far away)
29+
// and stop spamming when bumper/cliff conditions disappear
30+
if (!(msg_bump->is_left_pressed || msg_bump->is_right_pressed) && !prev_bumper)
2831
return;
2932

3033
prev_bumper = msg_bump->is_left_pressed || msg_bump->is_right_pressed;
3134

32-
// For any of {left/center/right} with no bumper/cliff event, we publish a faraway point that won't get used
35+
// For any of {left/center/right} with no bumper/cliff event, we publish a faraway point that won't get used
3336
if (msg_bump->is_left_pressed && !(msg_bump->is_right_pressed))
3437
{
3538
memcpy(&pointcloud_.data[0 * pointcloud_.point_step + pointcloud_.fields[0].offset], &p_side_x_, sizeof(float));
@@ -50,7 +53,7 @@ void Bumper2PcNodelet::bumperSensorCB(const ca_msgs::Bumper::ConstPtr& msg_bump)
5053
memcpy(&pointcloud_.data[1 * pointcloud_.point_step + pointcloud_.fields[0].offset], &P_INF_X, sizeof(float));
5154
}
5255

53-
if (msg_bump->is_right_pressed && !(msg_bump->is_left_pressed))
56+
if (msg_bump->is_right_pressed && !(msg_bump->is_left_pressed))
5457
{
5558
memcpy(&pointcloud_.data[2 * pointcloud_.point_step + pointcloud_.fields[0].offset], &p_side_x_, sizeof(float));
5659
memcpy(&pointcloud_.data[2 * pointcloud_.point_step + pointcloud_.fields[1].offset], &n_side_y_, sizeof(float));
@@ -71,15 +74,22 @@ void Bumper2PcNodelet::cliffSensorCB(const ca_msgs::Cliff::ConstPtr& msg_cliff)
7174
if (pointcloud_pub_.getNumSubscribers() == 0)
7275
return;
7376

74-
// We publish just one "no events" pc (with all three points far away) and stop spamming when bumper/cliff conditions disappear
75-
if ( !(msg_cliff->is_cliff_left || msg_cliff->is_cliff_front_left || msg_cliff->is_cliff_front_right || msg_cliff->is_cliff_right)
76-
&& !prev_cliff)
77+
// We publish just one "no events" pc (with all three points far away)
78+
// and stop spamming when bumper/cliff conditions disappear
79+
if (!(msg_cliff->is_cliff_left ||
80+
msg_cliff->is_cliff_front_left ||
81+
msg_cliff->is_cliff_front_right ||
82+
msg_cliff->is_cliff_right)
83+
&& !prev_cliff)
7784
return;
7885

79-
prev_cliff = msg_cliff->is_cliff_left || msg_cliff->is_cliff_front_left || msg_cliff->is_cliff_front_right || msg_cliff->is_cliff_right;
86+
prev_cliff = msg_cliff->is_cliff_left ||
87+
msg_cliff->is_cliff_front_left ||
88+
msg_cliff->is_cliff_front_right ||
89+
msg_cliff->is_cliff_right;
90+
8091

81-
82-
// For any of {left/center/right} with no bumper/cliff event, we publish a faraway point that won't get used
92+
// For any of {left/center/right} with no bumper/cliff event, we publish a faraway point that won't get used
8393
if (msg_cliff->is_cliff_left)
8494
{
8595
memcpy(&pointcloud_.data[0 * pointcloud_.point_step + pointcloud_.fields[0].offset], &p_side_x_, sizeof(float));
@@ -126,15 +136,17 @@ void Bumper2PcNodelet::onInit()
126136
// them will probably fail.
127137
std::string base_link_frame;
128138
double r, h, angle;
129-
nh.param("pointcloud_radius", r, 0.25); pc_radius_ = r;
130-
nh.param("pointcloud_height", h, 0.04); pc_height_ = h;
131-
nh.param("side_point_angle", angle, 0.34906585);
139+
nh.param("pointcloud_radius", r, 0.25);
140+
pc_radius_ = r;
141+
nh.param("pointcloud_height", h, 0.04);
142+
pc_height_ = h;
143+
nh.param("side_point_angle", angle, 0.34906585);
132144
nh.param<std::string>("base_link_frame", base_link_frame, "/base_link");
133145

134146
// Lateral points x/y coordinates; we need to store float values to memcopy later
135-
p_side_x_ = + pc_radius_*sin(angle); // angle degrees from vertical
136-
p_side_y_ = + pc_radius_*cos(angle); // angle degrees from vertical
137-
n_side_y_ = - pc_radius_*cos(angle); // angle degrees from vertical
147+
p_side_x_ = + pc_radius_ * sin(angle); // angle degrees from vertical
148+
p_side_y_ = + pc_radius_ * cos(angle); // angle degrees from vertical
149+
n_side_y_ = - pc_radius_ * cos(angle); // angle degrees from vertical
138150

139151
// Prepare constant parts of the pointcloud message to be published
140152
pointcloud_.header.frame_id = base_link_frame;
@@ -180,7 +192,7 @@ void Bumper2PcNodelet::onInit()
180192
ROS_INFO("Bumper/cliff pointcloud configured at distance %f and height %f from base frame", pc_radius_, pc_height_);
181193
}
182194

183-
} // namespace create_bumper2pc
195+
} // namespace create_bumper2pc
184196

185197

186198
PLUGINLIB_EXPORT_CLASS(create_bumper2pc::Bumper2PcNodelet, nodelet::Nodelet);

Diff for: ca_description/CMakeLists.txt

+6
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,12 @@ catkin_package()
1010

1111
roslaunch_add_file_check(launch)
1212

13+
install(DIRECTORY scripts/
14+
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
15+
USE_SOURCE_PERMISSIONS
16+
PATTERN ".svn" EXCLUDE
17+
)
18+
1319
install(
1420
DIRECTORY launch meshes urdf
1521
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}

Diff for: ca_description/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
<buildtool_depend>catkin</buildtool_depend>
1616

1717
<build_depend>roslaunch</build_depend>
18+
<build_depend>tf</build_depend>
1819

1920
<exec_depend>joint_state_publisher</exec_depend>
2021
<exec_depend>robot_state_publisher</exec_depend>

Diff for: ca_driver/CMakeLists.txt

+7-5
Original file line numberDiff line numberDiff line change
@@ -3,15 +3,15 @@ project(ca_driver)
33

44
add_compile_options(-std=c++11)
55

6-
find_package(libcreate REQUIRED)
7-
86
find_package(catkin REQUIRED COMPONENTS
97
ca_msgs
108
diagnostic_msgs
119
diagnostic_updater
1210
geometry_msgs
11+
libcreate
1312
nav_msgs
1413
roscpp
14+
roslint
1515
sensor_msgs
1616
std_msgs
1717
tf
@@ -24,17 +24,16 @@ catkin_package(
2424
diagnostic_msgs
2525
diagnostic_updater
2626
geometry_msgs
27+
libcreate
2728
nav_msgs
2829
roscpp
2930
sensor_msgs
3031
std_msgs
3132
tf
32-
DEPENDS libcreate
3333
)
3434

3535
include_directories(
3636
include
37-
${libcreate_INCLUDE_DIRS}
3837
${catkin_INCLUDE_DIRS}
3938
)
4039

@@ -58,6 +57,9 @@ install(DIRECTORY include
5857
FILES_MATCHING PATTERN "*.h"
5958
)
6059

61-
install(DIRECTORY launch config
60+
install(DIRECTORY config launch
6261
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
6362
)
63+
64+
set(ROSLINT_CPP_OPTS "--filter=-build/c++11, -runtime/references")
65+
roslint_cpp()

0 commit comments

Comments
 (0)