Skip to content

Commit

Permalink
minor advanced session fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
JeremyZoss committed Jul 19, 2022
1 parent d161058 commit ff3d598
Show file tree
Hide file tree
Showing 13 changed files with 126 additions and 93 deletions.
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 2.8.3)
project(lesson_perception)
add_definitions(-std=c++11)
add_definitions(-std=c++14)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 2.8.3)
project(lesson_perception)
add_definitions(-std=c++11)
add_definitions(-std=c++14)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
Expand Down
21 changes: 14 additions & 7 deletions exercises/5.3/src/filter_call/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.0.2)
project(filter_call)

## Compile as C++11, supported in ROS Kinetic and newer
Expand Down Expand Up @@ -68,7 +68,7 @@ catkin_python_setup()
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# perception_msgs
# std_msgs # Or other packages containing msgs
# )

################################################
Expand Down Expand Up @@ -103,7 +103,7 @@ catkin_python_setup()
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES filter_call
# CATKIN_DEPENDS perception_msgs roscpp rospy
# CATKIN_DEPENDS rospy
# DEPENDS system_lib
)

Expand Down Expand Up @@ -157,16 +157,23 @@ include_directories(

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )

## Mark cpp header files for installation
Expand Down
9 changes: 6 additions & 3 deletions exercises/5.3/src/filter_call/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,13 @@
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="rchristopher@todo.todo">rchristopher</maintainer>
<maintainer email="ubuntu@todo.todo">ubuntu</maintainer>


<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>BSD</license>
<license>TODO</license>


<!-- Url tags are optional, but multiple are allowed, one per tag -->
Expand Down Expand Up @@ -49,7 +49,10 @@
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<depend>rospy</depend>
<build_depend>rospy</build_depend>
<build_export_depend>rospy</build_export_depend>
<exec_depend>rospy</exec_depend>


<!-- The export tag contains other, unspecified, tags -->
<export>
Expand Down
34 changes: 18 additions & 16 deletions exercises/5.3/src/filter_call/scripts/filter_call.py
Original file line number Diff line number Diff line change
@@ -1,22 +1,24 @@
#!/usr/bin/env python

import rospy
import lesson_perception.srv
import py_perception.srv
from sensor_msgs.msg import PointCloud2

if __name__ == '__main__':
rospy.init_node('filter_cloud', anonymous=True)
rospy.wait_for_service('filter_cloud')
try:
rospy.init_node('filter_cloud', anonymous=True)
rospy.wait_for_service('filter_cloud')

# =======================
# VOXEL GRID FILTER
# =======================

srvp = rospy.ServiceProxy('filter_cloud', lesson_perception.srv.FilterCloud)
req = lesson_perception.srv.FilterCloudRequest()
srvp = rospy.ServiceProxy('filter_cloud', py_perception.srv.FilterCloud)
req = py_perception.srv.FilterCloudRequest()
req.pcdfilename = rospy.get_param('~pcdfilename', '')
req.operation = lesson_perception.srv.FilterCloudRequest.VOXELGRID
# FROM THE SERVICE, ASSIGN POINTS
req.operation = py_perception.srv.FilterCloudRequest.VOXELGRID

# FROM THE SERVICE, ASSIGN POINTS
req.input_cloud = PointCloud2()

# ERROR HANDLING
Expand All @@ -38,10 +40,10 @@
# PASSTHROUGH FILTER
# =======================

srvp = rospy.ServiceProxy('filter_cloud', lesson_perception.srv.FilterCloud)
req = lesson_perception.srv.FilterCloudRequest()
srvp = rospy.ServiceProxy('filter_cloud', py_perception.srv.FilterCloud)
req = py_perception.srv.FilterCloudRequest()
req.pcdfilename = ''
req.operation = lesson_perception.srv.FilterCloudRequest.PASSTHROUGH
req.operation = py_perception.srv.FilterCloudRequest.PASSTHROUGH
# FROM THE SERVICE, ASSIGN POINTS
req.input_cloud = res_voxel.output_cloud

Expand All @@ -60,10 +62,10 @@
# PLANE SEGMENTATION
# =======================

srvp = rospy.ServiceProxy('filter_cloud', lesson_perception.srv.FilterCloud)
req = lesson_perception.srv.FilterCloudRequest()
srvp = rospy.ServiceProxy('filter_cloud', py_perception.srv.FilterCloud)
req = py_perception.srv.FilterCloudRequest()
req.pcdfilename = ''
req.operation = lesson_perception.srv.FilterCloudRequest.PLANESEGMENTATION
req.operation = py_perception.srv.FilterCloudRequest.PLANESEGMENTATION
# FROM THE SERVICE, ASSIGN POINTS
req.input_cloud = res_pass.output_cloud

Expand All @@ -82,10 +84,10 @@
# CLUSTER EXTRACTION
# =======================

srvp = rospy.ServiceProxy('filter_cloud', lesson_perception.srv.FilterCloud)
req = lesson_perception.srv.FilterCloudRequest()
srvp = rospy.ServiceProxy('filter_cloud', py_perception.srv.FilterCloud)
req = py_perception.srv.FilterCloudRequest()
req.pcdfilename = ''
req.operation = lesson_perception.srv.FilterCloudRequest.CLUSTEREXTRACTION
req.operation = py_perception.srv.FilterCloudRequest.CLUSTEREXTRACTION
# FROM THE SERVICE, ASSIGN POINTS
req.input_cloud = res_seg.output_cloud

Expand Down
2 changes: 1 addition & 1 deletion exercises/5.3/src/filter_call/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from catkin_pkg.python_setup import generate_distutils_setup
# fetch values from package.xml
setup_args = generate_distutils_setup(
packages=[''],
packages=['filter_call'],
package_dir={'': 'include'},
)
setup(**setup_args)
Original file line number Diff line number Diff line change
@@ -1,16 +1,20 @@
cmake_minimum_required(VERSION 2.8.3)
project(lesson_perception)
add_definitions(-std=c++11)
project(py_perception)
add_definitions(-std=c++14)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
sensor_msgs
std_msgs
message_generation
visualization_msgs
tf
pcl_ros
)
find_package(Python REQUIRED COMPONENTS Development)
#find_package(PCL REQUIRED)

## System dependencies are found with CMake's conventions
Expand Down Expand Up @@ -69,7 +73,8 @@ find_package(catkin REQUIRED COMPONENTS
# Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
sensor_msgs
sensor_msgs
visualization_msgs
)

###################################
Expand All @@ -83,11 +88,14 @@ find_package(catkin REQUIRED COMPONENTS
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES lesson_perception
# LIBRARIES py_perception
CATKIN_DEPENDS
roscpp
rospy
sensor_msgs
std_msgs
message_runtime
visualization_msgs
tf
pcl_ros
# DEPENDS system_lib
Expand All @@ -106,7 +114,7 @@ include_directories(
)

## Declare a cpp library
# add_library(lesson_perception
# add_library(py_perception
# src/${PROJECT_NAME}/lesson_perception.cpp
# )

Expand All @@ -121,6 +129,7 @@ include_directories(
target_link_libraries(py_perception_node
${catkin_LIBRARIES}
# ${PCL_LIBRARIES}
Python::Module
)

#############
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<?xml version="1.0"?>
<package format="2">
<name>lesson_perception</name>
<name>py_perception</name>
<version>0.0.0</version>
<description>The lesson_perception package</description>
<description>The py_perception package</description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
Expand Down Expand Up @@ -43,7 +43,12 @@
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
<depend>tf</depend>
<depend>pcl_conversions</depend>
<depend>pcl_msgs</depend>
<depend>pcl_ros</depend>
<depend>visualization_msgs</depend>
<depend>std_msgs</depend>
<depend>rospy</depend>

<!-- The export tag contains other, unspecified, tags -->
<export>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include <sensor_msgs/PointCloud2.h> //hydro
#include <lesson_perception/FilterCloud.h>
#include <py_perception/FilterCloud.h>

// PCL specific includes
#include <pcl_conversions/pcl_conversions.h> //hydro
Expand Down Expand Up @@ -95,7 +95,7 @@ pcl::PointCloud<pcl::PointXYZ>::Ptr planeSegmentation(const pcl::PointCloud<pcl:
seg.setOptimizeCoefficients (true);
seg.setModelType (pcl::SACMODEL_PLANE);
seg.setMethodType (pcl::SAC_RANSAC);
seg.setMaxIterations (200);
seg.setMaxIterations (100);
seg.setDistanceThreshold (0.01); //keep as 1cm
// Segment the largest planar component from the cropped cloud
seg.setInputCloud (cropped_cloud);
Expand Down Expand Up @@ -165,57 +165,55 @@ clusterExtraction(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &input_cloud)
* ========================================*/

/* ========================================
* Fill Code: FILTER CALLBACK
* Fill Code: SERVICE
* ========================================*/
bool filterCallback(lesson_perception::FilterCloud::Request& request,
lesson_perception::FilterCloud::Response& response)
bool filterCallback(py_perception::FilterCloud::Request& request,
py_perception::FilterCloud::Response& response)
{
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud (new pcl::PointCloud<pcl::PointXYZ>);

if (request.pcdfilename.empty())
{
pcl::fromROSMsg(request.input_cloud, *cloud);
ROS_INFO_STREAM("cloud size: " << cloud->size());
ROS_INFO_STREAM("cloud size: " <<cloud->size());
if (cloud->empty())
{
ROS_ERROR("input cloud empty");
response.success = false;
return false;
}
}
else
{
pcl::io::loadPCDFile(request.pcdfilename, *cloud);
}

if (cloud->empty())
{
ROS_ERROR("input cloud empty");
response.success = false;
return false;
}

switch (request.operation)
{

case lesson_perception::FilterCloud::Request::VOXELGRID :
case py_perception::FilterCloud::Request::VOXELGRID :
{
filtered_cloud = voxelGrid(cloud, 0.01);
break;
}
case lesson_perception::FilterCloud::Request::PASSTHROUGH :
case py_perception::FilterCloud::Request::PASSTHROUGH :
{
filtered_cloud = passThrough(cloud);
break;
}
case lesson_perception::FilterCloud::Request::PLANESEGMENTATION :
case py_perception::FilterCloud::Request::PLANESEGMENTATION :
{
filtered_cloud = planeSegmentation(cloud);
break;
}
case lesson_perception::FilterCloud::Request::CLUSTEREXTRACTION :
case py_perception::FilterCloud::Request::CLUSTEREXTRACTION :
{
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> temp =clusterExtraction(cloud);
if (temp.size()>0)
{
filtered_cloud = temp[0];
}
//filtered_cloud = clusterExtraction(cloud)[0];
break;
}
default :
Expand All @@ -224,7 +222,7 @@ bool filterCallback(lesson_perception::FilterCloud::Request& request,
return false;
}

}
}

/*
* SETUP RESPONSE
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#request
sensor_msgs/PointCloud2 input_cloud
string topic
#if empty, use data present in input_cloud
string pcdfilename

# Removes objects outside a defined grid pattern x,y,z
Expand Down
4 changes: 3 additions & 1 deletion exercises/python-pcl_ws/src/py_perception/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 2.8.3)
project(py_perception)
add_definitions(-std=c++11)
add_definitions(-std=c++14)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
Expand All @@ -14,6 +14,7 @@ find_package(catkin REQUIRED COMPONENTS
tf
pcl_ros
)
find_package(Python REQUIRED COMPONENTS Development)
#find_package(PCL REQUIRED)

## System dependencies are found with CMake's conventions
Expand Down Expand Up @@ -128,6 +129,7 @@ include_directories(
target_link_libraries(py_perception_node
${catkin_LIBRARIES}
# ${PCL_LIBRARIES}
Python::Module
)

#############
Expand Down

0 comments on commit ff3d598

Please sign in to comment.