Skip to content

Commit

Permalink
Merge pull request #919 from stereolabs/improve_od
Browse files Browse the repository at this point in the history
Fix Object Detection and add missing feature
  • Loading branch information
Myzhar authored Sep 22, 2023
2 parents 8833d25 + e0cd1f0 commit 71eb2bb
Show file tree
Hide file tree
Showing 12 changed files with 209 additions and 197 deletions.
8 changes: 8 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,14 @@
CHANGELOG
=========

2023-09-15
----------
- Remove start_object_detection and stop_object_detection services
- Add enable_object_detection service that takes a bool as parameter to enable/disable the OD module (same behavior as in ROS 2 Wrapper)
- Add parameter 'object_detection/allow_reduced_precision_inference'
- Add parameter 'object_detection/prediction_timeout'
- The parameter 'object_detection/model' is no more an integer, but a string with the full name of the supported OD model

2023-09-15
----------
- Add pose and odometry status publishers
Expand Down
3 changes: 2 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ The zed_ros_wrapper is a catkin package. It depends on the following ROS package
- sensor_msgs
- stereo_msgs
- std_msgs
- std_srvs
- message_filters
- tf2_ros
- nodelet
Expand Down Expand Up @@ -106,7 +107,7 @@ The SDK v3.0 introduces the Object Detection and Tracking module. **The Object D

The Object Detection can be enabled *automatically* when the node start setting the parameter `object_detection/od_enabled` to `true` in the file `common.yaml`.

The Object Detection can be enabled/disabled *manually* calling the services `start_object_detection` and `stop_object_detection`.
The Object Detection can be enabled/disabled *manually* calling the service `enable_object_detection`.

### Body Tracking
The Body Tracking module is not available for the ZED ROS Wrapper. Please consider migrating to the [ZED ROS2 Wrapper](https://github.com/stereolabs/zed-ros2-wrapper) if you need it.
Expand Down
1 change: 1 addition & 0 deletions zed_nodelets/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ find_package(catkin REQUIRED COMPONENTS
sensor_msgs
stereo_msgs
std_msgs
std_srvs
message_filters
tf2_ros
nodelet
Expand Down
21 changes: 8 additions & 13 deletions zed_nodelets/src/zed_nodelet/include/zed_wrapper_nodelet.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
#include <visualization_msgs/Marker.h>
#include <std_srvs/SetBool.h>

#include <sl/Camera.hpp>

Expand All @@ -50,11 +51,9 @@
#include <zed_interfaces/set_led_status.h>
#include <zed_interfaces/set_pose.h>
#include <zed_interfaces/start_3d_mapping.h>
#include <zed_interfaces/start_object_detection.h>
#include <zed_interfaces/start_remote_stream.h>
#include <zed_interfaces/start_svo_recording.h>
#include <zed_interfaces/stop_3d_mapping.h>
#include <zed_interfaces/stop_object_detection.h>
#include <zed_interfaces/stop_remote_stream.h>
#include <zed_interfaces/stop_svo_recording.h>
#include <zed_interfaces/toggle_led.h>
Expand Down Expand Up @@ -395,15 +394,9 @@ class ZEDWrapperNodelet : public nodelet::Nodelet
*/
bool on_save_3d_map(zed_interfaces::save_3d_map::Request& req, zed_interfaces::save_3d_map::Response& res);

/*! \brief Service callback to start_object_detection service
/*! \brief Service callback to enable_object_detection service
*/
bool on_start_object_detection(zed_interfaces::start_object_detection::Request& req,
zed_interfaces::start_object_detection::Response& res);

/*! \brief Service callback to stop_object_detection service
*/
bool on_stop_object_detection(zed_interfaces::stop_object_detection::Request& req,
zed_interfaces::stop_object_detection::Response& res);
bool on_enable_object_detection(std_srvs::SetBool::Request& req, std_srvs::SetBool::Response& res);

/*! \brief Service callback to save_area_memory service
*/
Expand Down Expand Up @@ -563,8 +556,7 @@ class ZEDWrapperNodelet : public nodelet::Nodelet
ros::ServiceServer mSrvStartMapping;
ros::ServiceServer mSrvStopMapping;
ros::ServiceServer mSrvSave3dMap;
ros::ServiceServer mSrvStartObjDet;
ros::ServiceServer mSrvStopObjDet;
ros::ServiceServer mSrvEnableObjDet;
ros::ServiceServer mSrvSaveAreaMemory;
ros::ServiceServer mSrvSetRoi;
ros::ServiceServer mSrvResetRoi;
Expand Down Expand Up @@ -807,19 +799,22 @@ class ZEDWrapperNodelet : public nodelet::Nodelet
bool mObjDetEnabled = false;
bool mObjDetRunning = false;
bool mObjDetTracking = true;
bool mObjDetReducedPrecision = false;
bool mObjDetBodyFitting = true;
float mObjDetConfidence = 50.f;
float mObjDetMaxRange = 10.f;
double mObjDetPredTimeout = 0.5;
std::vector<sl::OBJECT_CLASS> mObjDetFilter;
bool mObjDetPeopleEnable = true;
bool mObjDetVehiclesEnable = true;
bool mObjDetBagsEnable = true;
bool mObjDetAnimalsEnable = true;
bool mObjDetElectronicsEnable = true;
bool mObjDetFruitsEnable = true;
bool mObjDetSportsEnable = true;
bool mObjDetSportEnable = true;

sl::OBJECT_DETECTION_MODEL mObjDetModel = sl::OBJECT_DETECTION_MODEL::MULTI_CLASS_BOX_MEDIUM;
sl::OBJECT_FILTERING_MODE mObjFilterMode = sl::OBJECT_FILTERING_MODE::NMS3D;

ros::Publisher mPubObjDet;
}; // class ZEDROSWrapperNodelet
Expand Down
Loading

0 comments on commit 71eb2bb

Please sign in to comment.