# ROS2 OpenVINO Runtime Framework Study
## Github
https://github.com/intel/ros2_openvino_toolkit
<br/>
## Architecture

<br/><br/>
## Logic Flow

<br/><br/>
## Features of dynamic_vino_sample
### Input Resource
|Input Resource|Description|
|--------------------|------------------------------------------------------------------|
|StandardCamera|Any RGB camera with USB port supporting. Currently only the first USB camera if many are connected.|
|RealSenseCamera| Intel RealSense RGB-D Camera, directly calling RealSense Camera via librealsense plugin of openCV.|
|ImageTopic| Any ROS topic which is structured in image message.|
|Image| Any image file which can be parsed by openCV, such as .png, .jpeg.|
|Video| Any video file which can be parsed by openCV.|
|IpCamera| Any RTSP server which can push video stream.|
<br/>
### Inference Feature
|Inference|Description|YAML Configuration|Model Used|
|-----------------------|------------------------------------------------------------------|----------------------|----------------------|
|Face Detection| Object Detection task applied to face recognition using a sequence of neural networks.|[pipeline_image.yaml](./sample/param/pipeline_image.yaml)<br>[pipeline_image_video.yaml](./sample/param/pipeline_image_video.yaml)<br>[pipeline_people.yaml](./sample/param/pipeline_people.yaml)<br>[pipeline_people_ip.yaml](./sample/param/pipeline_people_ip.yaml)|[face-detection-adas-0001](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/face-detection-adas-0001)<br>[age-gender-recognition-retail-0013](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/age-gender-recognition-retail-0013)<br>[emotions-recognition-retail-0003](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/emotions-recognition-retail-0003)<br>[head-pose-estimation-adas-0001](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/head-pose-estimation-adas-0001)|
|Emotion Recognition| Emotion recognition based on detected face image.|[pipeline_image.yaml](./sample/param/pipeline_image.yaml)<br>[pipeline_image_video.yaml](./sample/param/pipeline_image_video.yaml)<br>[pipeline_people.yaml](./sample/param/pipeline_people.yaml)<br>[pipeline_people_ip.yaml](./sample/param/pipeline_people_ip.yaml)|[emotions-recognition-retail-0003](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/emotions-recognition-retail-0003)|
|Age & Gender Recognition| Age and gender recognition based on detected face image.|[pipeline_image.yaml](./sample/param/pipeline_image.yaml)<br>[pipeline_image_video.yaml](./sample/param/pipeline_image_video.yaml)<br>[pipeline_people.yaml](./sample/param/pipeline_people.yaml)<br>[pipeline_people_ip.yaml](./sample/param/pipeline_people_ip.yaml)|[age-gender-recognition-retail-0013](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/age-gender-recognition-retail-0013)|
|Head Pose Estimation| Head pose estimation based on detected face image.|[pipeline_image.yaml](./sample/param/pipeline_image.yaml)<br>[pipeline_image_video.yaml](./sample/param/pipeline_image_video.yaml)<br>[pipeline_people.yaml](./sample/param/pipeline_people.yaml)<br>[pipeline_people_ip.yaml](./sample/param/pipeline_people_ip.yaml)|[head-pose-estimation-adas-0001](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/head-pose-estimation-adas-0001)|
|Object Detection| Object detection based on SSD-based trained models.|[pipeline_object.yaml](./sample/param/pipeline_object.yaml)<br>[pipeline_object_topic.yaml](./sample/param/pipeline_object_topic.yaml)|[mobilenet-ssd](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/public/mobilenet-ssd)|
|Vehicle and License Detection| Vehicle and license detection based on Intel models.|[pipeline_vehicle_detection.yaml](./sample/param/pipeline_vehicle_detection.yaml)|[vehicle-license-plate-detection-barrier-0106](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/vehicle-license-plate-detection-barrier-0106)<br>[vehicle-attributes-recognition-barrier-0039](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/vehicle-attributes-recognition-barrier-0039)<br>[license-plate-recognition-barrier-0001](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/license-plate-recognition-barrier-0001)|
|Object Segmentation| Object segmentation.|[pipeline_segmentation.yaml](./sample/param/pipeline_segmentation.yaml)<br>[pipeline_segmentation_image.yaml](./sample/param/pipeline_segmentation_image.yaml)<br>[pipeline_video.yaml](./sample/param/pipeline_video.yaml)|[semantic-segmentation-adas-0001](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/semantic-segmentation-adas-0001)<br>[deeplabv3](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/public/deeplabv3)|
|Person Attributes| Person attributes based on object detection.|[pipeline_person_attributes.yaml](./sample/param/pipeline_person_attributes.yaml)|[person-attributes-recognition-crossroad-0230](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/person-attributes-recognition-crossroad-0230)<br>[person-detection-retail-0013](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/person-detection-retail-0013)|
|Person Reidentification|Person reidentification based on object detection.|[pipeline_person_reidentification.yaml](./sample/param/pipeline_reidentification.yaml)|[person-detection-retail-0013](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/person-detection-retail-0013)<br>[person-reidentification-retail-0277](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/intel/person-reidentification-retail-0277)|
|Object Segmentation Maskrcnn| Object segmentation and detection based on maskrcnn model.|[pipeline_segmentation_maskrcnn.yaml](./sample/param/pipeline_segmentation_maskrcnn.yaml)|[mask_rcnn_inception_v2_coco_2018_01_28](https://github.com/openvinotoolkit/open_model_zoo/tree/releases/2022/3/models/public/mask_rcnn_inception_resnet_v2_atrous_coco)|
<br/>
### Published Topic
|Inference|Published Topic|
|---|---|
|People Detection|```/ros2_openvino_toolkit/face_detection```([object_msgs:msg:ObjectsInBoxes](https://github.com/intel/ros2_object_msgs/blob/master/msg/ObjectsInBoxes.msg))|
|Emotion Recognition|```/ros2_openvino_toolkit/emotions_recognition```([object_msgs:msg:EmotionsStamped](../../../object_msgs/msg/EmotionsStamped.msg))|
|Age and Gender Recognition|```/ros2_openvino_toolkit/age_genders_Recognition```([object_msgs:msg:AgeGenderStamped](../../../object_msgs/msg/AgeGenderStamped.msg))|
|Head Pose Estimation|```/ros2_openvino_toolkit/headposes_estimation```([object_msgs:msg:HeadPoseStamped](../../../object_msgs/msg/HeadPoseStamped.msg))|
|Object Detection|```/ros2_openvino_toolkit/detected_objects```([object_msgs::msg::ObjectsInBoxes](https://github.com/intel/ros2_object_msgs/blob/master/msg/ObjectsInBoxes.msg))|
|Object Segmentation|```/ros2_openvino_toolkit/segmented_obejcts```([object_msgs::msg::ObjectsInMasks](../../../object_msgs/msg/ObjectsInMasks.msg))|
|Object Segmentation Maskrcnn|```/ros2_openvino_toolkit/segmented_obejcts```([object_msgs::msg::ObjectsInMasks](../../../object_msgs/msg/ObjectsInMasks.msg))|
|Person Reidentification|```/ros2_openvino_toolkit/reidentified_persons```([object_msgs::msg::ReidentificationStamped](../../../object_msgs/msg/ReidentificationStamped.msg))|
|Vehicle Detection|```/ros2_openvino_toolkit/detected_vehicles_attribs```([object_msgs::msg::VehicleAttribsStamped](../../../object_msgs/msg/PersonAttributeStamped.msg))|
|Vehicle License Detection|```/ros2_openvino_toolkit/detected_license_plates```([object_msgs::msg::LicensePlateStamped](../../../object_msgs/msg/LicensePlateStamped.msg))|
<br/>
## Service
|Inference|Service|
|---|---|
|Object Detection Service|```/detect_object```([object_msgs::srv::DetectObject](https://github.com/intel/ros2_object_msgs/blob/master/srv/DetectObject.srv))|
|Face Detection Service|```/detect_face```([object_msgs::srv::DetectObject](https://github.com/intel/ros2_object_msgs/blob/master/srv/DetectObject.srv))|
|Age Gender Detection Service|```/detect_age_gender```([object_msgs::srv::AgeGender](./object_msgs/srv/AgeGenderSrv.srv))|
|Headpose Detection Service|```/detect_head_pose```([object_msgs::srv::HeadPose](./object_msgs/srv/HeadPoseSrv.srv))|
|Emotion Detection Service|```/detect_emotion```([object_msgs::srv::Emotion](./object_msgs/srv/EmotionSrv.srv))|
<br/>
## Launch program
```
$ source setup-env-rss.bash
$ ros2 launch dynamic_vino_sample pipeline_object.launch.py
```
* **pipeline_object.launch.py**
```python
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
import launch_ros.actions
from launch.substitutions import LaunchConfiguration, PythonExpression
import launch
def generate_launch_description():
return LaunchDescription([
launch.actions.DeclareLaunchArgument(name='yaml_path', default_value =
os.path.join(get_package_share_directory('dynamic_vino_sample'), 'param','pipeline_object.yaml')),
# Openvino detection
launch_ros.actions.Node(
package='dynamic_vino_sample',
executable='pipeline_with_params',
arguments=['-config', LaunchConfiguration('yaml_path')],
remappings=[
('/openvino_toolkit/object/detected_objects',
'/ros2_openvino_toolkit/detected_objects'),
('/openvino_toolkit/object/images',
'/ros2_openvino_toolkit/image_rviz')],
output='screen'),
# Rviz
#launch_ros.actions.Node(
# package='rviz2', node_executable='rviz2', output='screen',
# arguments=['--display-config', default_rviz]),
])
```
<br/><br/>
* **pipeline_object.yaml**
```yaml
Pipelines:
- name: object
inputs: [StandardCamera]
infers:
- name: ObjectDetection
model: /opt/openvino_toolkit/models/public/ssd_mobilenet_v2_coco/FP16/ssd_mobilenet_v2_coco.xml
engine: CPU
label: /opt/openvino_toolkit/models/public/ssd_mobilenet_v2_coco/FP16/ssd_mobilenet_v2_coco.labels
batch: 1
confidence_threshold: 0.5
enable_roi_constraint: true # set enable_roi_constraint to false if you don't want to make the inferred ROI (region of interest) constrained into the camera frame
outputs: [ImageWindow, RosTopic, RViz]
connects:
- left: StandardCamera
right: [ObjectDetection]
- left: ObjectDetection
right: [ImageWindow, RosTopic, RViz]
OpenvinoCommon:
```

<br/>
**ssd_mobilenet_v2_coco.xml**
```xml
<?xml version="1.0" ?>
<net name="ssd_mobilenet_v2_coco" version="10">
<layers>
<layer id="0" name="image_tensor" type="Parameter" version="opset1">
<data shape="1, 3, 300, 300" element_type="f16"/>
<output>
<port id="0" precision="FP16">
<dim>1</dim>
<dim>3</dim>
<dim>300</dim>
<dim>300</dim>
</port>
</output>
</layer>
<layer id="1" name="Preprocessor/mul/x" type="Const" version="opset1">
<data element_type="f16" shape="1, 1, 1, 1" offset="0" size="2"/>
<output>
<port id="0" precision="FP16" names="Preprocessor/mul/x:0">
<dim>1</dim>
<dim>1</dim>
<dim>1</dim>
<dim>1</dim>
</port>
</output>
</layer>
<layer id="2" name="Preprocessor/mul" type="Multiply" version="opset1">
<data auto_broadcast="numpy"/>
<input>
<port id="0" precision="FP16">
<dim>1</dim>
<dim>1</dim>
<dim>1</dim>
<dim>1</dim>
</port>
<port id="1" precision="FP16">
<dim>1</dim>
<dim>3</dim>
<dim>300</dim>
<dim>300</dim>
</port>
</input>
<output>
<port id="2" precision="FP16" names="Preprocessor/mul:0">
<dim>1</dim>
<dim>3</dim>
<dim>300</dim>
<dim>300</dim>
</port>
</output>
</layer>
.
.
.
```
<br/>
**ssd_mobilenet_v2_coco.labels**
```
__background__
person
bicycle
car
motorcycle
airplan
bus
train
truck
boat
trafficlight
firehydrant
streetsign
stopsign
parkingmeter
bench
bird
cat
dog
horse
sheep
cow
elephant
bear
zebra
giraffe
hat
backpack
umbrella
shoe
eyeglasses
handbag
tie
suitcase
frisbee
skis
snowboard
sportsball
kite
baseballbat
baseballglove
skateboard
surfboard
tennisracket
bottle
plate
wineglass
cup
fork
knife
spoon
bowl
banana
apple
sandwich
orange
broccoli
carrot
hotdog
pizza
donut
cake
chair
couch
pottedplant
bed
mirror
diningtable
window
desk
toilet
door
tv
laptop
mouse
remote
keyboard
cellphone
microwave
oven
toaster
sink
refrigerator
blender
book
clock
vase
scissors
teddybear
hairdrier
toothbrush
hairbrush
```
<br/>
Result:

<br/>
## Create pipline
/my_ros2_ws/src/ros2_openvino_toolkit/sample/pipeline_with_params.cpp
```cpp
void signalHandler(int signum)
{
slog::warn << "!!!!!!!!!!!Interrupt signal (" << signum << ") received!!!!!!!!!!!!" << slog::endl;
// cleanup and close up stuff here
// terminate program
PipelineManager::getInstance().stopAll();
// exit(signum);
}
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec;
rclcpp::Node::SharedPtr main_node = rclcpp::Node::make_shared("openvino_pipeline");
rclcpp::Node::SharedPtr service_node = std::make_shared<vino_service::PipelineProcessingServer
<pipeline_srv_msgs::srv::PipelineSrv>>("pipeline_service");
// register signal SIGINT and signal handler
//signal(SIGINT, signalHandler);
try {
std::cout << "InferenceEngine: " << InferenceEngine::GetInferenceEngineVersion() << std::endl;
// ----- Parsing and validation of input args-----------------------
std::string config = getConfigPath(argc, argv);
if(config.empty()){
throw std::runtime_error("Config File is not correctly set.");
return -1;
}
slog::info << "Config File Path =" << config << slog::endl;
Params::ParamManager::getInstance().parse(config);
Params::ParamManager::getInstance().print();
auto pipelines = Params::ParamManager::getInstance().getPipelines();
if (pipelines.size() < 1) {
throw std::logic_error("Pipeline parameters should be set!");
}
// auto createPipeline = PipelineManager::getInstance().createPipeline;
for (auto & p : pipelines) {
PipelineManager::getInstance().createPipeline(p, main_node);
}
PipelineManager::getInstance().runAll();
//rclcpp::spin(main_node);
exec.add_node(main_node);
exec.add_node(service_node);
exec.spin();
PipelineManager::getInstance().stopAll();
rclcpp::shutdown();
} catch (const std::exception & error) {
slog::err << error.what() << slog::endl;
return -2;
} catch (...) {
slog::err << "Unknown/internal exception happened." << slog::endl;
return -3;
}
return 0;
}
```
<br/><br/>
**Manage pipline**
/my_ros2_ws/src/ros2_openvino_toolkit/dynamic_vino_lib/src/pipeline_manager.cpp
```cpp
std::shared_ptr<Pipeline>
PipelineManager::createPipeline(const Params::ParamManager::PipelineRawData & params,
rclcpp::Node::SharedPtr node)
{
if (params.name == "") {
throw std::logic_error("The name of pipeline won't be empty!");
}
std::shared_ptr<Pipeline> pipeline = std::make_shared<Pipeline>(params.name);
pipeline->getParameters()->update(params);
PipelineData data;
data.parent_node = node;
data.pipeline = pipeline;
data.params = params;
data.state = PipelineState_ThreadNotCreated;
auto inputs = parseInputDevice(data);
if (inputs.size() != 1) {
slog::err << "currently one pipeline only supports ONE input." << slog::endl;
return nullptr;
}
for (auto it = inputs.begin(); it != inputs.end(); ++it) {
pipeline->add(it->first, it->second);
auto node = it->second->getHandler();
if (node != nullptr) {
data.spin_nodes.emplace_back(node);
}
}
auto outputs = parseOutput(data);
for (auto it = outputs.begin(); it != outputs.end(); ++it) {
pipeline->add(it->first, it->second);
}
auto infers = parseInference(params);
for (auto it = infers.begin(); it != infers.end(); ++it) {
pipeline->add(it->first, it->second);
}
slog::info << "Updating connections ..." << slog::endl;
for (auto it = params.connects.begin(); it != params.connects.end(); ++it) {
pipeline->add(it->first, it->second);
}
// slog::info << "Updateing filters ..." << slog::endl;
// pipeline->addFilters(params.filters);
pipelines_.insert({params.name, data});
pipeline->setCallback();
slog::info << "One Pipeline Created!" << slog::endl;
pipeline->printPipeline();
return pipeline;
}
std::map<std::string, std::shared_ptr<Outputs::BaseOutput>>
PipelineManager::parseOutput(const PipelineData & pdata)
{
std::map<std::string, std::shared_ptr<Outputs::BaseOutput>> outputs;
for (auto & name : pdata.params.outputs) {
slog::info << "Parsing Output: " << name << slog::endl;
std::shared_ptr<Outputs::BaseOutput> object = nullptr;
if (name == kOutputTpye_RosTopic) {
object = std::make_shared<Outputs::RosTopicOutput>(pdata.params.name, pdata.parent_node);
} else if (name == kOutputTpye_ImageWindow) {
object = std::make_shared<Outputs::ImageWindowOutput>(pdata.params.name);
} else if (name == kOutputTpye_RViz) {
object = std::make_shared<Outputs::RvizOutput>(pdata.params.name, pdata.parent_node);
} else if (name == kOutputTpye_RosService) {
object = std::make_shared<Outputs::RosServiceOutput>(pdata.params.name);
} else {
slog::err << "Invalid output name: " << name << slog::endl;
}
if (object != nullptr) {
outputs.insert({name, object});
slog::info << " ... Adding one Output: " << name << slog::endl;
}
}
return outputs;
}
std::shared_ptr<dynamic_vino_lib::BaseInference>
PipelineManager::createObjectDetection(
const Params::ParamManager::InferenceRawData & infer)
{
std::shared_ptr<Models::ObjectDetectionModel> object_detection_model;
std::shared_ptr<dynamic_vino_lib::ObjectDetection> object_inference_ptr;
slog::debug << "for test in createObjectDetection()" << slog::endl;
if (infer.model_type == kInferTpye_ObjectDetectionTypeSSD) {
object_detection_model =
std::make_shared<Models::ObjectDetectionSSDModel>(infer.label, infer.model, infer.batch);
}
if (infer.model_type == kInferTpye_ObjectDetectionTypeYolov2) {
object_detection_model =
std::make_shared<Models::ObjectDetectionYolov2Model>(infer.label, infer.model, infer.batch);
}
slog::debug << "for test in createObjectDetection(), Created SSDModel" << slog::endl;
object_inference_ptr = std::make_shared<dynamic_vino_lib::ObjectDetection>(
infer.enable_roi_constraint, infer.confidence_threshold); // To-do theshold configuration
slog::debug << "for test in createObjectDetection(), before modelInit()" << slog::endl;
object_detection_model->modelInit();
auto object_detection_engine = engine_manager_.createEngine(
infer.engine, object_detection_model);
slog::debug << "for test in createObjectDetection(), before loadNetwork" << slog::endl;
object_inference_ptr->loadNetwork(object_detection_model);
object_inference_ptr->loadEngine(object_detection_engine);
slog::debug << "for test in createObjectDetection(), OK" << slog::endl;
return object_inference_ptr;
}
void PipelineManager::runAll()
{
for (auto it = pipelines_.begin(); it != pipelines_.end(); ++it) {
if (it->second.state != PipelineState_ThreadRunning) {
it->second.state = PipelineState_ThreadRunning;
}
if (service_.state != PipelineState_ThreadRunning) {
service_.state = PipelineState_ThreadRunning;
}
if (it->second.thread == nullptr) {
it->second.thread = std::make_shared<std::thread>(&PipelineManager::threadPipeline, this,
it->second.params.name.c_str());
}
}
}
```
<br/><br/>
**Create publisher and handle output**
/my_ros2_ws/src/ros2_openvino_toolkit/dynamic_vino_lib/src/outputs/ros_topic_output.cpp
<br/><br/>
```cpp
Outputs::RosTopicOutput::RosTopicOutput(std::string output_name,
const rclcpp::Node::SharedPtr node)
: BaseOutput(output_name)
{
...
pub_detected_object_ = node_->create_publisher<object_msgs::msg::ObjectsInBoxes>(
"/openvino_toolkit/" + output_name_ + "/detected_objects", 16);
...
}
void Outputs::RosTopicOutput::accept(
const std::vector<dynamic_vino_lib::FaceDetectionResult> & results)
{
faces_topic_ = std::make_shared<object_msgs::msg::ObjectsInBoxes>();
object_msgs::msg::ObjectInBox face;
for (auto r : results) {
// slog::info << ">";
auto loc = r.getLocation();
face.roi.x_offset = loc.x;
face.roi.y_offset = loc.y;
face.roi.width = loc.width;
face.roi.height = loc.height;
face.object.object_name = r.getLabel();
face.object.probability = r.getConfidence();
faces_topic_->objects_vector.push_back(face);
detected_objects_topic_->objects_vector.push_back(face);
}
}
void Outputs::RosTopicOutput::handleOutput()
{
auto header = getPipeline()->getInputDevice()->getLockedHeader();
...
if (detected_objects_topic_ != nullptr) {
// slog::info << "publishing detected objects outputs." << slog::endl;
detected_objects_topic_->header = header;
pub_detected_object_->publish(*detected_objects_topic_);
detected_objects_topic_ = nullptr;
}
}
...
```
<br/><br/>
## Generic OpenVINO Sample
<br/><br/>
# Reference
## Pre-trained Object
| Item | Objects | Remark |
|------|----------------|------------|
| 1 | person | 人 |
| 2 | bicycle | 自行車 |
| 3 | car | 汽車 |
| 4 | motorcycle | 摩托車 |
| 5 | airplan | 飛機 |
| 6 | bus | 公車 |
| 7 | train | 火車 |
| 8 | truck | 卡車 |
| 9 | boat | 船 |
| 10 | traffic light | 交通燈 |
| 11 | fire hydrant | 消防栓 |
| 12 | street sign | 街道標誌 |
| 13 | stop sign | 停車標誌 |
| 14 | parking meter | 停車計時器 |
| 15 | bench | 長椅 |
| 16 | bird | 鳥 |
| 17 | cat | 貓 |
| 18 | dog | 狗 |
| 19 | horse | 馬 |
| 20 | sheep | 綿羊 |
| 21 | cow | 牛 |
| 22 | elephant | 大象 |
| 23 | bear | 熊 |
| 24 | zebra | 斑馬 |
| 25 | giraffe | 長頸鹿 |
| 26 | hat | 帽子 |
| 27 | backpack | 背包 |
| 28 | umbrella | 雨傘 |
| 29 | shoe | 鞋子 |
| 30 | eye glasses | 眼鏡 |
| 31 | handbag | 手提包 |
| 32 | tie | 領帶 |
| 33 | suitcase | 行李箱 |
| 34 | frisbee | 飛盤 |
| 35 | skis | 滑雪板 |
| 36 | snowboard | 雪地板 |
| 37 | sports ball | 運動球 |
| 38 | kite | 風箏 |
| 39 | baseball bat | 棒球棒 |
| 40 | baseball glove | 棒球手套 |
| 41 | skateboard | 滑板 |
| 42 | surfboard | 衝浪板 |
| 43 | tennis racket | 網球拍 |
| 44 | bottle | 瓶子 |
| 45 | plate | 盤子 |
| 46 | wine glass | 紅酒杯 |
| 47 | cup | 杯子 |
| 48 | fork | 叉子 |
| 49 | knife | 刀子 |
| 50 | spoon | 湯匙 |
| 51 | bowl | 碗 |
| 52 | banana | 香蕉 |
| 53 | apple | 蘋果 |
| 54 | sandwich | 三明治 |
| 55 | orange | 橙子 |
| 56 | broccoli | 花椰菜 |
| 57 | carrot | 胡蘿蔔 |
| 58 | hot dog | 熱狗 |
| 59 | pizza | 披薩 |
| 60 | donut | 甜甜圈 |
| 61 | cake | 蛋糕 |
| 62 | chair | 椅子 |
| 63 | couch | 沙發 |
| 64 | potted plant | 盆栽植物 |
| 65 | bed | 床 |
| 66 | mirror | 鏡子 |
| 67 | dining table | 餐桌 |
| 68 | window | 窗戶 |
| 69 | desk | 書桌 |
| 70 | toilet | 馬桶 |
| 71 | door | 門 |
| 72 | tv | 電視 |
| 73 | laptop | 筆記型電腦 |
| 74 | mouse | 滑鼠 |
| 75 | remote | 遙控器 |
| 76 | keyboard | 鍵盤 |
| 77 | cell phone | 手機 |
| 78 | microwave | 微波爐 |
| 79 | oven | 烤箱 |
| 80 | toaster | 烤麵包機 |
| 81 | sink | 水槽 |
| 82 | refrigerator | 冰箱 |
| 83 | blender | 搅拌機 |
| 84 | book | 書 |
| 85 | clock | 鐘 |
| 86 | vase | 花瓶 |
| 87 | scissors | 剪刀 |
| 88 | teddy bear | 泰迪熊 |
| 89 | hair drier | 吹風機 |
| 90 | toothbrush | 牙刷 |
| 91 | hair brush | 髮刷 |
<br/>