Skip to content

A ros demo for people detection and tracking on DJI M100 drone

Notifications You must be signed in to change notification settings

fan0210/DJIM100-people-detect-track

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

23 Commits
 
 
 
 
 
 

Repository files navigation

DJIM100-people-detect-track

A ros demo for people detection and tracking on DJI M100 drone

Building project

1.Prerequisites

2.Create a workspace and compile

mkdir -p ~/catkin_ws/src

next, copy all packages to /catkin_ws/src and

catkin_make

Usage

  • Set your own image topic

    find ros_people_detect.launch, ros_kcf_node.launch, dji_sdk_client.launch, and replace /image_pub/image with your own image topic.

  • Run dji_sdk_client and dji_sdk

    roslaunch dji_sdk_demo dji_sdk_client.launch roslaunch dji_sdk sdk_manifold.launch

  • Run people_detect node

    roslaunch people_detect ros_people_detect.launch

  • Run ros_kcf node

    roslaunch ros_kcf ros_kcf_node.launch

  • Remote control

    Now, you can use your remote control with custom functions to control the stop and start of tracking and detection. The control interface is defined in client.cpp.

    void StartMission1Callback(DJIDrone *drone)
    {
        drone->request_sdk_permission_control();
        sleep(1);
    
        ros::Rate loop_rate(50);
    
        while(ros::ok())
        {
            ros::spinOnce();
            drone->attitude_control(0x4B,forwardV,leftrV,heightV,yawV);
            cout<<fixed<<setprecision(2)<<"          "<<forwardV<<"  "<<leftrV<<"  "<<heightV<<"  "<<yawV<<endl;
            loop_rate.sleep();
        }
    }
    

    This callback function is used to start the task, that is to start the autonomous detection and tracking.

    void StartMission2Callback(DJIDrone *drone)
    {
        std_srvs::Empty srv;
        start_tracking.call(srv);
    }
    

    This callback function is used to start tracking, that is, people_detect node give a target to kcf_track node. In fact, this goal is the closest person to the center of the image, and if there is no people is detected, the tracking program will not run, but when any people is detected again, the tracking program will automatic run.

    void StartMission3Callback(DJIDrone *drone)
    {
        std_srvs::Empty srv;
        if(stop_detecting.call(srv))
        {
            sleep(1);
            detect_stop.call(srv);
        }
    }
    

    This callback function is used to start and stop people detecting.

    void StartMission4Callback(DJIDrone *drone)
    {
        std_srvs::Empty srv;
        if(stop_tracking.call(srv))
        {
            sleep(1);
            track_stop.call(srv);
        }
    }
    

    This callback function is used to stop kcf tracker.

Show results

videos:
autonomous detection and tracking.mp4

img1 load error img2 load error

About

A ros demo for people detection and tracking on DJI M100 drone

Topics

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published