Skip to content

Commit

Permalink
Fix Linting
Browse files Browse the repository at this point in the history
  • Loading branch information
Emiliano Borghi committed Jan 11, 2020
1 parent 292d43f commit 23e75d6
Show file tree
Hide file tree
Showing 39 changed files with 809 additions and 724 deletions.
5 changes: 3 additions & 2 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -49,5 +49,6 @@ script:
# Run tests
- catkin_make run_tests && catkin_test_results
# Lint package files
# - sudo apt-get install python-catkin-lint
# - catkin lint -W2 --strict --explain src
- sudo apt-get install python-catkin-lint
- catkin lint -W2 --strict --explain src/create_autonomy --ignore plugin_missing_install --ignore missing_depend --ignore target_name_collision
- catkin_make roslint
2 changes: 1 addition & 1 deletion ca_bringup/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<package format="2">
<name>ca_bringup</name>
<version>0.0.0</version>
<description>The ca_bringup package</description>
<description>ca_bringup spawns the nodes that the real robot uses</description>

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

Expand Down
25 changes: 17 additions & 8 deletions ca_bumper2pc/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,26 +1,32 @@
cmake_minimum_required(VERSION 2.8.3)
project(ca_bumper2pc)
find_package(catkin REQUIRED COMPONENTS
roscpp
ca_msgs
nodelet
pluginlib
ca_msgs
roscpp
roslint
sensor_msgs
)

catkin_package(
INCLUDE_DIRS include
LIBRARIES ca_bumper2pc_nodelet
CATKIN_DEPENDS roscpp nodelet pluginlib sensor_msgs ca_msgs
LIBRARIES ${PROJECT_NAME}_nodelet
CATKIN_DEPENDS
ca_msgs
nodelet
pluginlib
roscpp
sensor_msgs
)

include_directories(include ${catkin_INCLUDE_DIRS})

add_library(ca_bumper2pc_nodelet src/ca_bumper2pc.cpp)
add_dependencies(ca_bumper2pc_nodelet ${catkin_EXPORTED_TARGETS})
target_link_libraries(ca_bumper2pc_nodelet ${catkin_LIBRARIES})
add_library(${PROJECT_NAME}_nodelet src/${PROJECT_NAME}.cpp)
add_dependencies(${PROJECT_NAME}_nodelet ${catkin_EXPORTED_TARGETS})
target_link_libraries(${PROJECT_NAME}_nodelet ${catkin_LIBRARIES})

install(TARGETS ca_bumper2pc_nodelet
install(TARGETS ${PROJECT_NAME}_nodelet
DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
)
install(DIRECTORY include/${PROJECT_NAME}/
Expand All @@ -32,3 +38,6 @@ install(DIRECTORY plugins
install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

set(ROSLINT_CPP_OPTS "--filter=-build/c++11")
roslint_cpp()
10 changes: 5 additions & 5 deletions ca_bumper2pc/include/ca_bumper2pc/ca_bumper2pc.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,9 +68,9 @@ class Bumper2PcNodelet : public nodelet::Nodelet
{
public:
Bumper2PcNodelet()
: P_INF_X(+100*sin(0.34906585)),
P_INF_Y(+100*cos(0.34906585)),
N_INF_Y(-100*cos(0.34906585)),
: P_INF_X(+100 * sin(0.34906585)),
P_INF_Y(+100 * cos(0.34906585)),
N_INF_Y(-100 * cos(0.34906585)),
ZERO(0), prev_bumper(0), prev_cliff(0) { }
~Bumper2PcNodelet() { }

Expand All @@ -94,7 +94,7 @@ class Bumper2PcNodelet : public nodelet::Nodelet
ros::Publisher pointcloud_pub_;
ros::Subscriber cliff_event_subscriber_ ;
ros::Subscriber bumper_event_subscriber_;

sensor_msgs::PointCloud2 pointcloud_;

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

} // namespace create_bumper2pc
} // namespace create_bumper2pc

#endif // _CA_BUMPER2PC_HPP_
9 changes: 5 additions & 4 deletions ca_bumper2pc/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,16 +15,17 @@

<buildtool_depend>catkin</buildtool_depend>

<build_depend>roscpp</build_depend>
<build_depend>ca_msgs</build_depend>
<build_depend>nodelet</build_depend>
<build_depend>pluginlib</build_depend>
<build_depend>ca_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>roslint</build_depend>
<build_depend>sensor_msgs</build_depend>

<run_depend>roscpp</run_depend>
<run_depend>ca_msgs</run_depend>
<run_depend>nodelet</run_depend>
<run_depend>pluginlib</run_depend>
<run_depend>ca_msgs</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>sensor_msgs</run_depend>

<export>
Expand Down
48 changes: 30 additions & 18 deletions ca_bumper2pc/src/ca_bumper2pc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
*
* @brief Bumper to pointcloud nodelet class implementation.
*
*
* Copyright 2020
*
**/

Expand All @@ -15,6 +15,8 @@

#include "ca_bumper2pc/ca_bumper2pc.hpp"

#include <string>

namespace create_bumper2pc
{

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

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

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

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

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

// We publish just one "no events" pc (with all three points far away) and stop spamming when bumper/cliff conditions disappear
if ( !(msg_cliff->is_cliff_left || msg_cliff->is_cliff_front_left || msg_cliff->is_cliff_front_right || msg_cliff->is_cliff_right)
&& !prev_cliff)
// We publish just one "no events" pc (with all three points far away)
// and stop spamming when bumper/cliff conditions disappear
if (!(msg_cliff->is_cliff_left ||
msg_cliff->is_cliff_front_left ||
msg_cliff->is_cliff_front_right ||
msg_cliff->is_cliff_right)
&& !prev_cliff)
return;

prev_cliff = msg_cliff->is_cliff_left || msg_cliff->is_cliff_front_left || msg_cliff->is_cliff_front_right || msg_cliff->is_cliff_right;
prev_cliff = msg_cliff->is_cliff_left ||
msg_cliff->is_cliff_front_left ||
msg_cliff->is_cliff_front_right ||
msg_cliff->is_cliff_right;



// For any of {left/center/right} with no bumper/cliff event, we publish a faraway point that won't get used
// For any of {left/center/right} with no bumper/cliff event, we publish a faraway point that won't get used
if (msg_cliff->is_cliff_left)
{
memcpy(&pointcloud_.data[0 * pointcloud_.point_step + pointcloud_.fields[0].offset], &p_side_x_, sizeof(float));
Expand Down Expand Up @@ -126,15 +136,17 @@ void Bumper2PcNodelet::onInit()
// them will probably fail.
std::string base_link_frame;
double r, h, angle;
nh.param("pointcloud_radius", r, 0.25); pc_radius_ = r;
nh.param("pointcloud_height", h, 0.04); pc_height_ = h;
nh.param("side_point_angle", angle, 0.34906585);
nh.param("pointcloud_radius", r, 0.25);
pc_radius_ = r;
nh.param("pointcloud_height", h, 0.04);
pc_height_ = h;
nh.param("side_point_angle", angle, 0.34906585);
nh.param<std::string>("base_link_frame", base_link_frame, "/base_link");

// Lateral points x/y coordinates; we need to store float values to memcopy later
p_side_x_ = + pc_radius_*sin(angle); // angle degrees from vertical
p_side_y_ = + pc_radius_*cos(angle); // angle degrees from vertical
n_side_y_ = - pc_radius_*cos(angle); // angle degrees from vertical
p_side_x_ = + pc_radius_ * sin(angle); // angle degrees from vertical
p_side_y_ = + pc_radius_ * cos(angle); // angle degrees from vertical
n_side_y_ = - pc_radius_ * cos(angle); // angle degrees from vertical

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

} // namespace create_bumper2pc
} // namespace create_bumper2pc


PLUGINLIB_EXPORT_CLASS(create_bumper2pc::Bumper2PcNodelet, nodelet::Nodelet);
6 changes: 6 additions & 0 deletions ca_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,12 @@ catkin_package()

roslaunch_add_file_check(launch)

install(DIRECTORY scripts/
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
USE_SOURCE_PERMISSIONS
PATTERN ".svn" EXCLUDE
)

install(
DIRECTORY launch meshes urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
Expand Down
1 change: 1 addition & 0 deletions ca_description/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<buildtool_depend>catkin</buildtool_depend>

<build_depend>roslaunch</build_depend>
<build_depend>tf</build_depend>

<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
Expand Down
12 changes: 7 additions & 5 deletions ca_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,15 @@ project(ca_driver)

add_compile_options(-std=c++11)

find_package(libcreate REQUIRED)

find_package(catkin REQUIRED COMPONENTS
ca_msgs
diagnostic_msgs
diagnostic_updater
geometry_msgs
libcreate
nav_msgs
roscpp
roslint
sensor_msgs
std_msgs
tf
Expand All @@ -24,17 +24,16 @@ catkin_package(
diagnostic_msgs
diagnostic_updater
geometry_msgs
libcreate
nav_msgs
roscpp
sensor_msgs
std_msgs
tf
DEPENDS libcreate
)

include_directories(
include
${libcreate_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)

Expand All @@ -58,6 +57,9 @@ install(DIRECTORY include
FILES_MATCHING PATTERN "*.h"
)

install(DIRECTORY launch config
install(DIRECTORY config launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

set(ROSLINT_CPP_OPTS "--filter=-build/c++11, -runtime/references")
roslint_cpp()
Loading

0 comments on commit 23e75d6

Please sign in to comment.