Skip to content

Commit

Permalink
Working IRL
Browse files Browse the repository at this point in the history
  • Loading branch information
jbrhm committed Jan 19, 2024
1 parent 65e776f commit e722684
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 8 deletions.
2 changes: 1 addition & 1 deletion launch/zed.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="use_builtin_visual_odom" default="false"/>

<rosparam command="load" file="$(find mrover)/config/perception.yaml" />
<node pkg="nodelet" type="nodelet" name="zed_nodelet" respawn="true"
<node pkg="nodelet" type="nodelet" name="zed" respawn="true"
args="load mrover/ZedNodelet nodelet_manager" output="screen">
<param name="use_builtin_visual_odom" value="$(arg use_builtin_visual_odom)"/>
</node>
Expand Down
12 changes: 9 additions & 3 deletions launch/zed_test.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,13 @@
<arg name="use_rtabmap_stereo_odom" default="false"/>
<arg name="use_builtin_visual_odom" default="false"/>

<!-- ZED DETECTION PARAMS -->
<arg name="obj_increment_weight" default="3"/>
<arg name="obj_decrement_weight" default="1"/>
<arg name="obj_hitcount_threshold" default="50"/>
<arg name="obj_hitcount_max" default="500"/>


<group if="$(arg run_rviz)">
<arg name="rvizconfig" default="$(find mrover)/config/rviz/zed_test.rviz"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)"/>
Expand All @@ -21,14 +28,13 @@
args="manager" output="screen"/>

<include file="$(find mrover)/launch/zed.launch">
<arg name="use_rtabmap_stereo_odom" value="$(arg use_rtabmap_stereo_odom)"/>
<arg name="use_builtin_visual_odom" value="$(arg use_builtin_visual_odom)"/>
</include>

<node if="$(arg run_object_detector)"
<!-- <node if="$(arg run_object_detector)"
pkg="nodelet" type="nodelet" name="object_detector" respawn="true"
args="load mrover/ObjectDetectorNodelet perception_nodelet_manager" output="screen">
</node>
</node> -->

<node if="$(arg run_tag_detector)"
pkg="nodelet" type="nodelet" name="tag_detector" respawn="true"
Expand Down
8 changes: 4 additions & 4 deletions src/perception/object_detector/object_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ namespace mrover {
mNh.param<std::string>("world_frame", mMapFrameId, "map");

//Read ROS Params
mNh.param<int>("obj_increment_weight", mObjIncrementWeight, 1);
mNh.param<int>("obj_decrement_weight", mObjDecrementWeight, 5);
mNh.param<int>("obj_decrement_threshold", mObjHitThreshold, 100);
mNh.param<int>("obj_max_hitcount", mObjMaxHitcount, 200);
mNh.param<int>("obj_increment_weight", mObjIncrementWeight, 2);
mNh.param<int>("obj_decrement_weight", mObjDecrementWeight, 1);
mNh.param<int>("obj_hitcount_threshold", mObjHitThreshold, 50);
mNh.param<int>("obj_hitcount_max", mObjMaxHitcount, 60);

//Initialize Object Hit Cout to Zeros
mHitCount = 0;
Expand Down

0 comments on commit e722684

Please sign in to comment.