Browse Source

周末ROS学习沙龙第二期-新增人脸检测代码

adam_zhuo 4 years ago
parent
commit
9edd10b7ce

+ 9 - 8
src/ros_test_pkg/CMakeLists.txt

@@ -10,6 +10,7 @@ project(ros_test_pkg)
 find_package(catkin REQUIRED COMPONENTS
   roscpp
   std_msgs
+  message_generation
 )
 
 ## System dependencies are found with CMake's conventions
@@ -46,10 +47,10 @@ find_package(catkin REQUIRED COMPONENTS
 ##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
 
 ## Generate messages in the 'msg' folder
-# add_message_files(
-#   FILES
-#   myMsg.msg
-# )
+add_message_files(
+  FILES
+  myMsg.msg
+)
 
 ## Generate services in the 'srv' folder
 # add_service_files(
@@ -66,10 +67,10 @@ find_package(catkin REQUIRED COMPONENTS
 # )
 
 ## Generate added messages and services with any dependencies listed here
-# generate_messages(
-#   DEPENDENCIES
-#   std_msgs
-# )
+generate_messages(
+  DEPENDENCIES
+  std_msgs
+)
 
 ################################################
 ## Declare ROS dynamic reconfigure parameters ##

+ 3 - 0
src/ros_test_pkg/msg/myMsg.msg

@@ -0,0 +1,3 @@
+string name
+int32 device_id
+float32 percent

+ 2 - 0
src/ros_test_pkg/package.xml

@@ -51,10 +51,12 @@
   <buildtool_depend>catkin</buildtool_depend>
   <build_depend>roscpp</build_depend>
   <build_depend>std_msgs</build_depend>
+  <build_depend>message_generation</build_depend>
   <build_export_depend>roscpp</build_export_depend>
   <build_export_depend>std_msgs</build_export_depend>
   <exec_depend>roscpp</exec_depend>
   <exec_depend>std_msgs</exec_depend>
+  <exec_depend>message_runtime</exec_depend>
 
 
   <!-- The export tag contains other, unspecified, tags -->

+ 30 - 0
src/ros_test_pkg/scripts/face_detection.py

@@ -0,0 +1,30 @@
+#!/usr/bin/env python
+import rospy, cv2, cv_bridge
+import face_recognition
+from sensor_msgs.msg import Image
+
+class Face_Detection:
+
+    def __init__(self):
+        self.bridge = cv_bridge.CvBridge()
+        self.image_sub = rospy.Subscriber("/usb_cam/image_raw", Image, self.image_callback)
+    
+    def image_callback(self, msg):
+        image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="bgr8")
+        image_resize = cv2.resize(image, (0, 0), fx=0.25, fy=0.25)
+
+        face_locations = face_recognition.face_locations(image_resize)
+
+        for (top, right, bottom, left) in face_locations:
+            top *= 4
+            right *= 4
+            bottom *= 4
+            left *= 4
+            cv2.rectangle(image, (left, top), (right, bottom), (0, 0, 255), 2)
+        cv2.imshow("face_detection", image)
+        cv2.waitKey(3)
+
+if __name__ == '__main__':
+    rospy.init_node("face_detection_adam")
+    Face_Detection()
+    rospy.spin()

+ 19 - 0
src/ros_test_pkg/scripts/topic_publisher.py

@@ -0,0 +1,19 @@
+#!/usr/bin/env python
+
+import rospy
+from std_msgs.msg import Int32
+
+class Publisher:
+    def __init__(self):
+        self.number_pub = rospy.Publisher("/count", Int32, queue_size=10)
+        rate = rospy.Rate(1)
+        number_count = 0
+        while not rospy.is_shutdown():
+            self.number_pub.publish(number_count)
+            number_count += 1
+            rate.sleep()
+
+if __name__ == "__main__":
+    rospy.init_node("topic_publisher")
+    Publisher()
+    rospy.spin()

+ 28 - 0
src/ros_test_pkg/src/base_topic_publisher.cpp

@@ -0,0 +1,28 @@
+#include "ros/ros.h"
+#include "std_msgs/Int32.h"
+
+int main(int argc, char **argv)
+{
+    ros::init(argc, argv, "topic_publisher");
+    ros::NodeHandle node_handle;
+
+    ros::Publisher pub_number = node_handle.advertise<std_msgs::Int32>("/count", 10);
+
+    ros::Rate rate(1);
+    int number_count = 0;
+    while (ros::ok())
+    {
+        std_msgs::Int32 msg;
+        msg.data = number_count;
+        pub_number.publish(msg);
+
+        ROS_INFO("%d",msg.data);
+
+        ros::spinOnce();
+        rate.sleep();
+        number_count++;
+    }
+
+    return 0;
+    
+}

+ 18 - 0
src/ros_test_pkg/src/base_topic_subscriber.cpp

@@ -0,0 +1,18 @@
+#include "ros/ros.h"
+#include "std_msgs/Int32.h"
+
+void num_callback(const std_msgs::Int32::ConstPtr& msg)
+{
+    ROS_INFO("Get Topic Msg: [%d]", msg->data);
+}
+
+int main(int argc, char **argv)
+{
+    ros::init(argc, argv, "topic_subsrciber");
+    ros::NodeHandle node_handle;
+
+    ros::Subscriber number_subscriber = node_handle.subscribe("/count", 10, num_callback);
+
+    ros::spin();
+    return 0;
+}

+ 29 - 0
src/ros_test_pkg/src/self_topic_publisher.cpp

@@ -0,0 +1,29 @@
+#include "ros/ros.h"
+#include "stdio.h"
+#include "ros_test_pkg/myMsg.h"
+
+int main(int argc, char **argv)
+{
+    ros::init(argc, argv, "topic_publisher");
+    ros::NodeHandle node_handle;
+
+    ros::Publisher pub_number = node_handle.advertise<ros_test_pkg::myMsg>("/count", 10);
+
+    ros::Rate rate(1);
+    int number_count = 0;
+    while (ros::ok())
+    {
+        ros_test_pkg::myMsg msg;
+        msg.name = "robot";
+        msg.device_id = number_count%5;
+        msg.percent = rand()/double(RAND_MAX);
+        pub_number.publish(msg);
+
+        ros::spinOnce();
+        rate.sleep();
+        number_count++;
+    }
+
+    return 0;
+    
+}

+ 19 - 0
src/ros_test_pkg/src/self_topic_subscriber.cpp

@@ -0,0 +1,19 @@
+#include "ros/ros.h"
+#include "ros_test_pkg/myMsg.h"
+
+void num_callback(const ros_test_pkg::myMsg::ConstPtr& msg)
+{
+    ROS_INFO("Msg.name: [%s], Msg.device_id: [%d], Msg.percent: [%f]", msg->name.c_str(),
+            msg->device_id, msg->percent);
+}
+
+int main(int argc, char **argv)
+{
+    ros::init(argc, argv, "topic_subsrciber");
+    ros::NodeHandle node_handle;
+
+    ros::Subscriber number_subscriber = node_handle.subscribe("/count", 10, num_callback);
+
+    ros::spin();
+    return 0;
+}

+ 7 - 6
src/ros_test_pkg/src/topic_publisher.cpp

@@ -1,23 +1,24 @@
 #include "ros/ros.h"
-#include "std_msgs/Int32.h"
+#include "stdio.h"
+#include "ros_test_pkg/myMsg.h"
 
 int main(int argc, char **argv)
 {
     ros::init(argc, argv, "topic_publisher");
     ros::NodeHandle node_handle;
 
-    ros::Publisher pub_number = node_handle.advertise<std_msgs::Int32>("/count", 10);
+    ros::Publisher pub_number = node_handle.advertise<ros_test_pkg::myMsg>("/count", 10);
 
     ros::Rate rate(1);
     int number_count = 0;
     while (ros::ok())
     {
-        std_msgs::Int32 msg;
-        msg.data = number_count;
+        ros_test_pkg::myMsg msg;
+        msg.name = "robot";
+        msg.device_id = number_count%5;
+        msg.percent = rand()/double(RAND_MAX);
         pub_number.publish(msg);
 
-        ROS_INFO("%d",msg.data);
-
         ros::spinOnce();
         rate.sleep();
         number_count++;

+ 4 - 3
src/ros_test_pkg/src/topic_subscriber.cpp

@@ -1,9 +1,10 @@
 #include "ros/ros.h"
-#include "std_msgs/Int32.h"
+#include "ros_test_pkg/myMsg.h"
 
-void num_callback(const std_msgs::Int32::ConstPtr& msg)
+void num_callback(const ros_test_pkg::myMsg::ConstPtr& msg)
 {
-    ROS_INFO("Get Topic Msg: [%d]", msg->data);
+    ROS_INFO("Msg.name: [%s], Msg.device_id: [%d], Msg.percent: [%f]", msg->name.c_str(),
+            msg->device_id, msg->percent);
 }
 
 int main(int argc, char **argv)