Skip to content

Commit

Permalink
Merge pull request #45 from igonzf/deploy
Browse files Browse the repository at this point in the history
Updated parameters
  • Loading branch information
igonzf authored Jul 17, 2024
2 parents 9256e7c + e06944f commit c4fae06
Show file tree
Hide file tree
Showing 13 changed files with 50 additions and 37 deletions.
6 changes: 3 additions & 3 deletions bt_nodes/perception/include/perception/IsDetected.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class IsDetected : public BT::ConditionNode
}

private:
void image_callback(const sensor_msg::msg::Image::SharedPtr msg);
void image_callback(const sensor_msgs::msg::Image::SharedPtr msg);
std::shared_ptr<rclcpp_cascade_lifecycle::CascadeLifecycleNode> node_;
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;

Expand All @@ -89,8 +89,8 @@ class IsDetected : public BT::ConditionNode
std::map<int, std::string> pose_names_;

bool pub_bb_img_{false};
rclcpp::Publisher<sensor_msg::msg::Image>::SharedPtr bb_img_pub_;
rclcpp::Subscription<sensor_msg::msg::Image>::SharedPtr img_sub_;
rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr bb_img_pub_;
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr img_sub_;

cv::Mat last_image_;
};
Expand Down
14 changes: 6 additions & 8 deletions bt_nodes/perception/src/perception/IsDetected.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,13 +69,13 @@ IsDetected::IsDetected(const std::string & xml_tag_name, const BT::NodeConfigura
getInput("pub_bb_img", pub_bb_img_);

if (pub_bb_img_) {
pub_bb_img_ = node_->create_publisher<sensor_msgs::msg::Image>(
bb_img_pub_ = node_->create_publisher<sensor_msgs::msg::Image>(
"/bb_img_best_detection", 10);
img_sub_ = node_->create_subscription<sensor_msgs::msg::Image>(
"/camera/color/image_raw", 10,
std::bind(&IsDetected::image_callback, this, _1));
} else {
pub_bb_img_ = nullptr;
bb_img_pub_ = nullptr;
img_sub_ = nullptr;
}

Expand Down Expand Up @@ -233,9 +233,6 @@ BT::NodeStatus IsDetected::tick()
RCLCPP_INFO(node_->get_logger(), "[IsDetected] %d detections after filter", frames_.size());
}



// pub->publish(detections[0].image);

setOutput("best_detection", detections[0].class_name);

Expand All @@ -250,7 +247,7 @@ BT::NodeStatus IsDetected::tick()
cv::Scalar(0, 0, 255), 2);

auto msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", last_image_).toImageMsg();
pub_bb_img_->publish(*msg);
bb_img_pub_->publish(*msg);
}

RCLCPP_DEBUG(node_->get_logger(), "[IsDetected] Detections sorted");
Expand All @@ -269,13 +266,14 @@ void IsDetected::image_callback(const sensor_msgs::msg::Image::SharedPtr msg)
{
cv_bridge::CvImagePtr image_rgb_ptr;
try {
image_rgb_ptr = cv_bridge::toCvCopy(msg->source_img, sensor_msgs::image_encodings::BGR8);
image_rgb_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
} catch (cv_bridge::Exception & e) {
RCLCPP_ERROR(get_logger(), "cv_bridge exception: %s", e.what());
RCLCPP_ERROR(node_->get_logger(), "cv_bridge exception: %s", e.what());
return;
}
last_image_ = image_rgb_ptr->image;

}
} // namespace perception

BT_REGISTER_NODES(factory) {
Expand Down
20 changes: 12 additions & 8 deletions robocup_bringup/bt_xml/carry_my_luggage.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
frame_name="initial"
initial_pose="{going_back}"
x_offset="0.0"
y_offset="2.0"
y_offset="0.0"
/>


Expand All @@ -32,23 +32,22 @@
<Action ID="Speak" param="{bag_direction}" say_text="I see you are pointing to the bag at my"/>
<Action ID="Speak" param="" say_text="I am on my way"/>
<Action ID="MoveTo" is_truncated="true" distance_tolerance="1.2" tf_frame="{bag_tf}"/>
<Action ID="MoveToPredefined" pose="offer" group_name="arm_torso"/>
<Action ID="Speak" param="" say_text="please put the bag in my gripper"/>
<Action ID="MoveToPredefined" pose="offer" group_name="arm_torso"/>
<Action ID="Speak" param="" say_text="please put the bag in my gripper"/>
<Delay delay_msec="140">
<Action ID="MoveToPredefined" pose="open" group_name="gripper"/>
</Delay>
<ReactiveSequence>

<RetryUntilSuccessful num_attempts="-1">
<Condition ID="IsDetected" cam_frame="head_front_camera_rgb_optical_frame" confidence="0.6" frames="{frames}" interest="person" max_depth="5" max_entities="1" order="depth"/>
</RetryUntilSuccessful>
<Action ID="FilterEntity" frame="person_0" lambda="0.1"/>
<Action ID="LookAt" tf_frame="person_0_filtered" />
</ReactiveSequence>
<Delay delay_msec="140">
<Delay delay_msec="300">
<Action ID="MoveToPredefined" pose="close" group_name="gripper"/>
</Delay>
<Delay delay_msec="300">
<Delay delay_msec="500">
<Action ID="MoveToPredefined" pose="home" group_name="arm_torso"/>
</Delay>
<Action ID="Speak" param="" say_text="Perfect, now i will follow you. Please stop at the end "/>
Expand All @@ -60,7 +59,13 @@
<Fallback>
<ReactiveSequence>
<RetryUntilSuccessful num_attempts="-1">
<Condition ID="IsDetected" cam_frame="head_front_camera_rgb_optical_frame" confidence="0.3" person_id="{person_id}" interest="person" max_depth="6.7" max_entities="1" order="color"/>
<Condition ID="IsDetected" cam_frame="head_front_camera_rgb_optical_frame"
confidence="0.6"
person_id="{person_id}"
interest="person"
max_depth="3.0"
max_entities="2"
order="color"/>
</RetryUntilSuccessful>
<Action ID="FilterEntity" frame="person_0" lambda="0.1"/>
<Action ID="LookAt" tf_frame="person_0_filtered"/>
Expand All @@ -69,7 +74,6 @@
robot_distance_to_person="1.0"
frame="person_0_filtered"
check_time="9.0"/>
<!-- <Condition ID="IsMoving" frame="person_0" position_buffer_dimension="50" threshold_time="4.0" velocity_tolerance="0.003"/> -->
<Action ID="FollowEntity" camera_frame="head_front_camera_rgb_optical_frame"
distance_tolerance="0.2"
frame_to_follow="person_0_filtered"
Expand Down
2 changes: 1 addition & 1 deletion robocup_bringup/bt_xml/gpsr.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<BehaviorTree ID="GPSR">
<Sequence>
<Action ID="SetupGPSR" plugins="{plugins}"/>
<SetBlackboard output_key="cam_frame" value="head_front_camera_color_optical_frame"/>
<SetBlackboard output_key="cam_frame" value="head_front_camera_link_color_optical_frame"/>
<!-- <Action ID="SetStartPosition" frame_name="instruction point" /> -->
<Action ID="SetWp"/>

Expand Down
2 changes: 1 addition & 1 deletion robocup_bringup/bt_xml/receptionist.xml
Original file line number Diff line number Diff line change
Expand Up @@ -274,7 +274,7 @@
order="color"
best_detection="{best_detection}"
/>
<Action ID="MoveAlongAxis" speed="0.5" distance="6.28" axis="z"/>
<Action ID="MoveAlongAxis" speed="-0.5" distance="6.28" axis="z"/>
</ReactiveFallback>
<Action ID="LookAt" tf_frame="{best_detection}"/>

Expand Down
2 changes: 1 addition & 1 deletion robocup_bringup/bt_xml/robot_inspection.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<RetryUntilSuccessful num_attempts="-1">
<Condition ID="IsDoorOpen" door_thfloatreshold="1.5"/>
</RetryUntilSuccessful>
<Action ID="MoveAlongAxis" speed="0.25" distance="1.8" axis="x"/>
<Action ID="MoveAlongAxis" speed="0.25" distance="0.8" axis="x"/>

<Action ID="MoveTo" is_truncated="false" distance_tolerance="0" tf_frame="inspection_zone"/>
<Action ID="Speak" param="" say_text="Please say ready when you finish the inspection"/>
Expand Down
14 changes: 10 additions & 4 deletions robocup_bringup/bt_xml/storing_groceries.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,14 +8,17 @@
<Action ID="InitGroceries"/>
<Action ID="Speak" say_text="Hi this is gentlebots. Can you please open the door "/>

<!-- <RetryUntilSuccessful num_attempts="-1">
<RetryUntilSuccessful num_attempts="-1">
<Condition ID="IsDoorOpen" door_thfloatreshold="1.5"/>
</RetryUntilSuccessful> -->
</RetryUntilSuccessful>

<Action ID="MoveAlongAxis" speed="0.25" distance="1.0" axis="x"/>

<Repeat num_cycles="5">
<Sequence>
<Action ID="MoveTo" distance_tolerance="1" tf_frame="table"/>
<Action ID="MoveJoint" joint_name="torso_lift_joint"
joint_value="0.23"
joint_value="0.3"
group_name="arm_torso"/>
<RetryUntilSuccessful num_attempts="-1">

Expand All @@ -33,15 +36,18 @@
max_depth="5"
max_entities="1"
order="depth"
best_detection="{best_detection}"/>
best_detection="{best_detection}"
pub_bb_img="true"/>

<Action ID="RemoveStringSuffix" string_to_remove="{best_detection}"
suffix="_"
result="{possible_pick}"/>
</Sequence>
</RetryUntilSuccessful>

<Action ID="ClearOctomap" />
<Action ID="Speak" say_text="I am detecting " param="{possible_pick}"/>
<Action ID="Speak" say_text="as you can see it on my chest"/>
<Action ID="Speak" say_text="Trying to pick it from the table "/>
<RetryUntilSuccessful num_attempts="-1">
<Sequence>
Expand Down
2 changes: 1 addition & 1 deletion robocup_bringup/config/gpsr/gpsr.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
behaviors_main:
ros__parameters:
use_sim_time: False
cam_frame: "head_front_camera_color_optical_frame"
cam_frame: "head_front_camera_link_color_optical_frame"
home_position: [54.701, 1.360, 0.001]
home_pose: "home"
offer_pose: "offer"
Expand Down
4 changes: 2 additions & 2 deletions robocup_bringup/config/inspection/tiago_nav_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ local_costmap:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.55
inflation_radius: 0.40
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
Expand Down Expand Up @@ -278,7 +278,7 @@ global_costmap:
robot_radius: 0.29
resolution: 0.05
track_unknown_space: true
plugins: ["static_layer", "inflation_layer"]
plugins: ["static_layer","obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
Expand Down
8 changes: 4 additions & 4 deletions robocup_bringup/config/receptionist/receptionist_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,11 @@
offer_pose: "offer"
person_id: 001122334455
waypoints_names: ["entrance", "party", "guest_confirmation"]
# allow_duplicate_names: false
# ARENA C:
waypoints: # [x, y, yaw] only 3 numbers!!
entrance: [-2.065, -2.304, 1.174]
party: [-2.725, -3.593, -2.210]
guest_confirmation: [-2.725, -3.593, 0.482]
entrance: [10.552, -8.863, -2.737]
party: [15.103, -8.220, -0.446]
guest_confirmation: [15.103, -8.220, -1.949]

behaviors_main:
ros__parameters:
Expand Down
9 changes: 7 additions & 2 deletions robocup_bringup/launch/dialog.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,13 @@ def generate_launch_description():
n_threads=4,
n_predict=-1,

model_repo="cstr/Spaetzle-v60-7b-Q4_0-GGUF",
model_filename="Spaetzle-v60-7b_Q4_0.gguf",
# uncomment this for GPSR:
# model_repo="cstr/Spaetzle-v60-7b-Q4_0-GGUF",
# model_filename="Spaetzle-v60-7b_Q4_0.gguf",

# comment this for GPSR:
model_repo='TheBloke/Marcoroni-7B-v3-GGUF',
model_filename='marcoroni-7b-v3.Q3_K_L.gguf',

prefix='\n\n### Instruction:\n',
suffix='\n\n### Response:\n',
Expand Down
2 changes: 1 addition & 1 deletion robocup_bringup/launch/receptionist_dependencies.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ def generate_launch_description():
),
launch_arguments={
'rviz': 'True',
'map': package_dir + '/maps/ir_lab.yaml',
'map': package_dir + '/maps/robocup_arena_1.yaml',
'params_file': package_dir +
'/config/receptionist/tiago_nav_params.yaml',
'slam_params_file': package_dir +
Expand Down
2 changes: 1 addition & 1 deletion robocup_bringup/launch/storing_dependencies.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ def generate_launch_description():
),
launch_arguments={
# 'namespace': 'perception_system',
'model': yolo_model, # change to pretrained
'model': "yolov8x-seg.pt", # change to pretrained
'input_image_topic': '/head_front_camera/rgb/image_raw',
'input_depth_topic': '/head_front_camera/depth/image_raw',
'input_depth_info_topic': '/head_front_camera/depth/camera_info',
Expand Down

0 comments on commit c4fae06

Please sign in to comment.