decreased the count of copying image.
added command to face_tracker_node.
This commit is contained in:
@@ -24,6 +24,7 @@
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <ros/package.h>
|
||||
#include <std_msgs/Bool.h>
|
||||
#include <std_msgs/String.h>
|
||||
#include <std_msgs/Int32.h>
|
||||
#include <sensor_msgs/JointState.h>
|
||||
|
@@ -64,7 +64,8 @@ class VisionDemo : public OPDemo
|
||||
|
||||
ros::Publisher module_control_pub_;
|
||||
ros::Publisher motion_index_pub_;
|
||||
ros::Publisher rgb_led_pub_;
|
||||
ros::Publisher rgb_led_pub_;
|
||||
ros::Publisher face_tracking_command_pub_;
|
||||
|
||||
ros::Subscriber buttuon_sub_;
|
||||
ros::Subscriber faceCoord_sub_;
|
||||
|
@@ -17,5 +17,6 @@
|
||||
<param name="displayed_Image" type="int" value="0" />
|
||||
<!-- <param name="publish" type="int" value="2" /> -->
|
||||
<param name="publish" type="int" value="3" />
|
||||
<param name="start_condition" type="bool" value="false" />
|
||||
</node>
|
||||
</launch>
|
||||
|
@@ -193,6 +193,10 @@ int main(int argc, char **argv)
|
||||
|
||||
//relax to fit output rate
|
||||
loop_rate.sleep();
|
||||
|
||||
// for debug
|
||||
if (checkManagerRunning(manager_name) == false)
|
||||
return 0;
|
||||
}
|
||||
|
||||
//exit program
|
||||
|
@@ -34,8 +34,7 @@ FaceTracker::FaceTracker()
|
||||
head_scan_pub_ = nh_.advertise<std_msgs::String>("/robotis/head_control/scan_command", 0);
|
||||
|
||||
face_position_sub_ = nh_.subscribe("/face_position", 1, &FaceTracker::facePositionCallback, this);
|
||||
face_tracking_command_sub_ = nh_.subscribe("/face_tracker/command", 1, &FaceTracker::faceTrackerCommandCallback,
|
||||
this);
|
||||
//face_tracking_command_sub_ = nh_.subscribe("/robotis/demo_command", 1, &FaceTracker::faceTrackerCommandCallback, this);
|
||||
}
|
||||
|
||||
FaceTracker::~FaceTracker()
|
||||
@@ -73,12 +72,14 @@ void FaceTracker::faceTrackerCommandCallback(const std_msgs::String::ConstPtr &m
|
||||
void FaceTracker::startTracking()
|
||||
{
|
||||
on_tracking_ = true;
|
||||
|
||||
ROS_INFO("Start Face tracking");
|
||||
}
|
||||
|
||||
void FaceTracker::stopTracking()
|
||||
{
|
||||
on_tracking_ = false;
|
||||
|
||||
ROS_INFO("Stop Face tracking");
|
||||
}
|
||||
|
||||
|
@@ -55,6 +55,11 @@ void VisionDemo::setDemoEnable()
|
||||
usleep(20 * 1000);
|
||||
|
||||
enable_ = true;
|
||||
|
||||
std_msgs::Bool command;
|
||||
command.data = enable_;
|
||||
face_tracking_command_pub_.publish(command);
|
||||
|
||||
face_tracker_.startTracking();
|
||||
|
||||
ROS_INFO("Start Vision Demo");
|
||||
@@ -68,6 +73,10 @@ void VisionDemo::setDemoDisable()
|
||||
is_tracking_ = false;
|
||||
tracking_status_ = FaceTracker::Waiting;
|
||||
enable_ = false;
|
||||
|
||||
std_msgs::Bool command;
|
||||
command.data = enable_;
|
||||
face_tracking_command_pub_.publish(command);
|
||||
}
|
||||
|
||||
void VisionDemo::process()
|
||||
@@ -95,7 +104,7 @@ void VisionDemo::process()
|
||||
tracking_status_ = tracking_status;
|
||||
|
||||
//is_tracking_ = is_tracked;
|
||||
std::cout << "Tracking : " << tracking_status << std::endl;
|
||||
//std::cout << "Tracking : " << tracking_status << std::endl;
|
||||
}
|
||||
|
||||
void VisionDemo::processThread()
|
||||
@@ -122,6 +131,7 @@ void VisionDemo::callbackThread()
|
||||
module_control_pub_ = nh.advertise<std_msgs::String>("/robotis/enable_ctrl_module", 0);
|
||||
motion_index_pub_ = nh.advertise<std_msgs::Int32>("/robotis/action/page_num", 0);
|
||||
rgb_led_pub_ = nh.advertise<robotis_controller_msgs::SyncWriteItem>("/robotis/sync_write_item", 0);
|
||||
face_tracking_command_pub_ = nh.advertise<std_msgs::Bool>("/face_tracking/command", 0);
|
||||
|
||||
buttuon_sub_ = nh.subscribe("/robotis/open_cr/button", 1, &VisionDemo::buttonHandlerCallback, this);
|
||||
faceCoord_sub_ = nh.subscribe("/faceCoord", 1, &VisionDemo::facePositionCallback, this);
|
||||
|
Reference in New Issue
Block a user