cleanup the code.

improved robotis op3 default demo.
This commit is contained in:
Kayman 2017-07-18 11:37:02 +09:00
parent 464ef98717
commit 54433c57cd
9 changed files with 215 additions and 159 deletions

View File

@ -39,12 +39,12 @@ namespace robotis_op
{
BallDetector::BallDetector()
: nh_(ros::this_node::getName()),
it_(this->nh_),
enable_(true),
params_config_(),
init_param_(false),
not_found_count_(0)
: nh_(ros::this_node::getName()),
it_(this->nh_),
enable_(true),
params_config_(),
init_param_(false),
not_found_count_(0)
{
has_path_ = nh_.getParam("yaml_path", param_path_);
@ -127,7 +127,7 @@ bool BallDetector::newImage()
void BallDetector::process()
{
if(enable_ == false)
if (enable_ == false)
return;
if (cv_img_ptr_sub_ != NULL)
@ -145,7 +145,7 @@ void BallDetector::process()
void BallDetector::publishImage()
{
if(enable_ == false)
if (enable_ == false)
return;
//image_raw topic
@ -171,7 +171,7 @@ void BallDetector::publishImage()
void BallDetector::publishCircles()
{
if(enable_ == false)
if (enable_ == false)
return;
if (circles_.size() == 0)
@ -198,10 +198,6 @@ void BallDetector::publishCircles()
//publish message
circles_pub_.publish(circles_msg_);
//ball_detecting process time
//ros::Duration _process_dur = ros::Time::now() - sub_time_;
//ROS_INFO_STREAM("== Ball detecting processing time : " << _process_dur);
}
void BallDetector::enableCallback(const std_msgs::Bool::ConstPtr &msg)
@ -211,7 +207,7 @@ void BallDetector::enableCallback(const std_msgs::Bool::ConstPtr &msg)
void BallDetector::imageCallback(const sensor_msgs::ImageConstPtr & msg)
{
if(enable_ == false)
if (enable_ == false)
return;
try
@ -272,7 +268,7 @@ void BallDetector::dynParamCallback(ball_detector::detectorParamsConfig &config,
void BallDetector::cameraInfoCallback(const sensor_msgs::CameraInfo & msg)
{
if(enable_ == false)
if (enable_ == false)
return;
camera_info_msg_ = msg;
@ -284,27 +280,27 @@ void BallDetector::printConfig()
return;
std::cout << "Detetctor Configuration:" << std::endl << " gaussian_blur_size: "
<< params_config_.gaussian_blur_size << std::endl << " gaussian_blur_sigma: "
<< params_config_.gaussian_blur_sigma << std::endl << " canny_edge_th: " << params_config_.canny_edge_th
<< std::endl << " hough_accum_resolution: " << params_config_.hough_accum_resolution << std::endl
<< " min_circle_dist: " << params_config_.min_circle_dist << std::endl << " hough_accum_th: "
<< params_config_.hough_accum_th << std::endl << " min_radius: " << params_config_.min_radius
<< std::endl << " max_radius: " << params_config_.max_radius << std::endl << " filter_h_min: "
<< params_config_.filter_threshold.h_min << std::endl << " filter_h_max: "
<< params_config_.filter_threshold.h_max << std::endl << " filter_s_min: "
<< params_config_.filter_threshold.s_min << std::endl << " filter_s_max: "
<< params_config_.filter_threshold.s_max << std::endl << " filter_v_min: "
<< params_config_.filter_threshold.v_min << std::endl << " filter_v_max: "
<< params_config_.filter_threshold.v_max << std::endl << " use_second_filter: "
<< params_config_.use_second_filter << std::endl << " filter2_h_min: "
<< params_config_.filter2_threshold.h_min << std::endl << " filter2_h_max: "
<< params_config_.filter2_threshold.h_max << std::endl << " filter2_s_min: "
<< params_config_.filter2_threshold.s_min << std::endl << " filter2_s_max: "
<< params_config_.filter2_threshold.s_max << std::endl << " filter2_v_min: "
<< params_config_.filter2_threshold.v_min << std::endl << " filter2_v_max: "
<< params_config_.filter2_threshold.v_max << std::endl << " ellipse_size: "
<< params_config_.ellipse_size << std::endl << " filter_image_to_debug: " << params_config_.debug
<< std::endl << std::endl;
<< params_config_.gaussian_blur_size << std::endl << " gaussian_blur_sigma: "
<< params_config_.gaussian_blur_sigma << std::endl << " canny_edge_th: " << params_config_.canny_edge_th
<< std::endl << " hough_accum_resolution: " << params_config_.hough_accum_resolution << std::endl
<< " min_circle_dist: " << params_config_.min_circle_dist << std::endl << " hough_accum_th: "
<< params_config_.hough_accum_th << std::endl << " min_radius: " << params_config_.min_radius
<< std::endl << " max_radius: " << params_config_.max_radius << std::endl << " filter_h_min: "
<< params_config_.filter_threshold.h_min << std::endl << " filter_h_max: "
<< params_config_.filter_threshold.h_max << std::endl << " filter_s_min: "
<< params_config_.filter_threshold.s_min << std::endl << " filter_s_max: "
<< params_config_.filter_threshold.s_max << std::endl << " filter_v_min: "
<< params_config_.filter_threshold.v_min << std::endl << " filter_v_max: "
<< params_config_.filter_threshold.v_max << std::endl << " use_second_filter: "
<< params_config_.use_second_filter << std::endl << " filter2_h_min: "
<< params_config_.filter2_threshold.h_min << std::endl << " filter2_h_max: "
<< params_config_.filter2_threshold.h_max << std::endl << " filter2_s_min: "
<< params_config_.filter2_threshold.s_min << std::endl << " filter2_s_max: "
<< params_config_.filter2_threshold.s_max << std::endl << " filter2_v_min: "
<< params_config_.filter2_threshold.v_min << std::endl << " filter2_v_max: "
<< params_config_.filter2_threshold.v_max << std::endl << " ellipse_size: "
<< params_config_.ellipse_size << std::endl << " filter_image_to_debug: " << params_config_.debug
<< std::endl << std::endl;
}
void BallDetector::saveConfig()
@ -364,23 +360,6 @@ void BallDetector::filterImage()
if (!in_image_.data)
return;
/*
cv::Mat imgCrCb, imgCr;
cv::cvtColor(in_image_, imgCrCb, cv::COLOR_BGR2YCrCb);
std::vector<cv::Mat> _channels;
cv::split(imgCrCb, _channels);
imgCr = _channels[2];
cv::inRange(imgCr, params_config_.filter_h_min, params_config_.filter_h_max, imgCr);
cv::erode(imgCr, imgCr, cv::getStructuringElement(cv::MORPH_ELLIPSE, cv::Size(5, 5)) );
cv::dilate(imgCr, imgCr, cv::getStructuringElement(cv::MORPH_ELLIPSE, cv::Size(5, 5)) );
cv::dilate(imgCr, imgCr, cv::getStructuringElement(cv::MORPH_ELLIPSE, cv::Size(5, 5)) );
cv::erode(imgCr, imgCr, cv::getStructuringElement(cv::MORPH_ELLIPSE, cv::Size(5, 5)) );
cv::cvtColor(imgCr, in_image_, cv::COLOR_GRAY2RGB);
*/
cv::Mat img_hsv, img_filtered;
cv::cvtColor(in_image_, img_hsv, cv::COLOR_RGB2HSV);
@ -394,15 +373,6 @@ void BallDetector::filterImage()
// mask
cv::Mat img_mask;
// mophology : open and close
//int ellipse_size = 30;
//int dilate_size = params_config_.max_radius; // dilate_size = ellipse_size * 10
//cv::erode(img_filtered, img_mask, cv::getStructuringElement(cv::MORPH_ELLIPSE, cv::Size(ellipse_size, ellipse_size)));
//cv::dilate(img_mask, img_mask,
// cv::getStructuringElement(cv::MORPH_ELLIPSE, cv::Size(dilate_size, dilate_size)));
//makeFilterMask(img_filtered, img_mask, ellipse_size);
// check hsv range
cv::Mat img_filtered2;
inRangeHsv(img_hsv, params_config_.filter2_threshold, img_filtered2);
@ -410,8 +380,6 @@ void BallDetector::filterImage()
makeFilterMaskFromBall(img_filtered, img_mask);
cv::bitwise_and(img_filtered2, img_mask, img_filtered2);
// mophology(img_filtered2, img_filtered2, params_config_.ellipse_size);
// or
cv::bitwise_or(img_filtered, img_filtered2, img_filtered);
}
@ -437,7 +405,7 @@ void BallDetector::makeFilterMask(const cv::Mat &source_img, cv::Mat &mask_img,
{
for (int j = 0; j < source_width; j++)
{
uint8_t pixel = source_img.at<uint8_t>(i, j);
uint8_t pixel = source_img.at < uint8_t > (i, j);
if (pixel == 0)
continue;
@ -452,7 +420,7 @@ void BallDetector::makeFilterMask(const cv::Mat &source_img, cv::Mat &mask_img,
if (mask_j < 0 || mask_j >= source_width)
continue;
mask_img.at<uchar>(mask_i, mask_j, 0) = 255;
mask_img.at < uchar > (mask_i, mask_j, 0) = 255;
}
}
}
@ -464,51 +432,22 @@ void BallDetector::makeFilterMaskFromBall(const cv::Mat &source_img, cv::Mat &ma
// source_img.
mask_img = cv::Mat::zeros(source_img.rows, source_img.cols, CV_8UC1);
if(circles_.size() == 0)
if (circles_.size() == 0)
return;
// channel : 1
if (source_img.channels() != 1)
return;
// for (int i = 0; i < circles_.size(); i++)
// {
// if (circles_[i][0] != -1)
// {
// // _center = cv::Point(cvRound(circles_[_i][0]), cvRound(circles_[_i][1]));
// int center_x = cvRound(circles_[i][0]);
// int center_y = cvRound(circles_[i][1]);
// int radius = cvRound(circles_[i][2]) * 1.5;
//
// for (int mask_i = center_y - radius; mask_i <= center_y + radius; mask_i++)
// {
// if (mask_i < 0 || mask_i >= source_img.rows)
// continue;
//
// int mask_offset = abs(mask_i - center_y) * 0.5;
//
// for (int mask_j = center_x - radius + mask_offset; mask_j <= center_x + radius - mask_offset; mask_j++)
// {
// if (mask_j < 0 || mask_j >= source_img.cols)
// continue;
//
// mask_img.at<uchar>(mask_i, mask_j, 0) = 255;
// }
// }
//
// }
// }
cv::Mat img_labels, stats, centroids;
int numOfLables = cv::connectedComponentsWithStats(source_img, img_labels,
stats, centroids, 8,CV_32S);
int numOfLables = cv::connectedComponentsWithStats(source_img, img_labels, stats, centroids, 8, CV_32S);
for (int j = 1; j < numOfLables; j++)
{
int area = stats.at<int>(j, cv::CC_STAT_AREA);
int left = stats.at<int>(j, cv::CC_STAT_LEFT);
int top = stats.at<int>(j, cv::CC_STAT_TOP);
int top = stats.at<int>(j, cv::CC_STAT_TOP);
int width = stats.at<int>(j, cv::CC_STAT_WIDTH);
int height = stats.at<int>(j, cv::CC_STAT_HEIGHT);
int height = stats.at<int>(j, cv::CC_STAT_HEIGHT);
int center_x = left + width * 0.5;
int center_y = top + height * 0.5;
@ -526,7 +465,7 @@ void BallDetector::makeFilterMaskFromBall(const cv::Mat &source_img, cv::Mat &ma
if (mask_j < 0 || mask_j >= source_img.cols)
continue;
mask_img.at<uchar>(mask_i, mask_j, 0) = 255;
mask_img.at < uchar > (mask_i, mask_j, 0) = 255;
}
}
}
@ -588,40 +527,31 @@ void BallDetector::houghDetection(const unsigned int imgEncoding)
cv::cvtColor(in_image_, gray_image, CV_RGB2GRAY);
//Reduce the noise so we avoid false circle detection
cv::GaussianBlur(gray_image, gray_image, cv::Size(params_config_.gaussian_blur_size, params_config_.gaussian_blur_size),
cv::GaussianBlur(gray_image, gray_image,
cv::Size(params_config_.gaussian_blur_size, params_config_.gaussian_blur_size),
params_config_.gaussian_blur_sigma);
//double hough_accum_th = (not_found_count_ < NOT_FOUND_TH) ?
// params_config_.hough_accum_th : params_config_.hough_accum_th * 0.5;
double hough_accum_th = params_config_.hough_accum_th;
// std::cout << "Not found : " << not_found_count_ << ", value : " << hough_accum_th << std::endl;
//Apply the Hough Transform to find the circles
cv::HoughCircles(gray_image, circles_current, CV_HOUGH_GRADIENT, params_config_.hough_accum_resolution,
params_config_.min_circle_dist, params_config_.canny_edge_th, hough_accum_th,
params_config_.min_radius, params_config_.max_radius);
//set found circles to circles set. Apply some condition if desired.
//for (int ii = 0; ii < circles_current.size(); ii++)
//{
// circles_.push_back(circles_current.at(ii));
// // std::cout << "circle " << ii << ": (" << circles.at(ii)[0] << "," << circles.at(ii)[1] << ")" << std::endl;
//}
if(circles_current.size() == 0)
if (circles_current.size() == 0)
not_found_count_ += 1;
else
not_found_count_ = 0;
double alpha = 0.2;
for(int ix = 0; ix < circles_current.size(); ix++)
for (int ix = 0; ix < circles_current.size(); ix++)
{
cv::Point2d center = cv::Point(circles_current[ix][0], circles_current[ix][1]);
double radius = circles_current[ix][2];
for(int prev_ix = 0; prev_ix < prev_circles.size(); prev_ix++)
for (int prev_ix = 0; prev_ix < prev_circles.size(); prev_ix++)
{
cv::Point2d prev_center = cv::Point(prev_circles[prev_ix][0], prev_circles[prev_ix][1]);
double prev_radius = prev_circles[prev_ix][2];
@ -629,13 +559,11 @@ void BallDetector::houghDetection(const unsigned int imgEncoding)
cv::Point2d diff = center - prev_center;
double radius_th = std::max(radius, prev_radius) * 0.75;
if(sqrt(diff.dot(diff)) < radius_th)
if (sqrt(diff.dot(diff)) < radius_th)
{
if(abs(radius - prev_radius) < radius_th)
if (abs(radius - prev_radius) < radius_th)
{
// std::cout << "circle - raw " << ix << ": (" << circles_current.at(ix)[0] << "," << circles_current.at(ix)[1] << ")" << std::endl;
circles_current[ix] = circles_current[ix] * alpha + prev_circles[prev_ix] * (1 - alpha);
// std::cout << "circle - lpf " << ix << ": (" << circles_current.at(ix)[0] << "," << circles_current.at(ix)[1] << ")" << std::endl;
}
break;
@ -659,11 +587,6 @@ void BallDetector::drawOutputImage()
for (ii = 0; ii < circles_.size(); ii++)
{
{
// cv::Point _center = cv::Point(cvRound(circles_[ii][0]), cvRound(circles_[ii][1]));
// int _radius = cvRound(circles_[ii][2]);
// cv::circle( out_image_, _center, 5, cv::Scalar(0,0,255), -1, 8, 0 );// circle center in green
// cv::circle( out_image_, _center, _radius, cv::Scalar(0,0,255), 3, 8, 0 );// circle outline in red
int this_radius = cvRound(circles_[ii][2]);
if (this_radius > radius)
{

View File

@ -54,10 +54,17 @@ namespace robotis_op
class BallTracker
{
public:
enum TrackingStatus
{
NotFound = -1,
Waiting = 0,
Found = 1,
};
BallTracker();
~BallTracker();
bool processTracking();
int processTracking();
void startTracking();
void stopTracking();
@ -83,6 +90,7 @@ class BallTracker
const double FOV_WIDTH;
const double FOV_HEIGHT;
const int NOT_FOUND_THRESHOLD;
const int WAITING_THRESHOLD;
const bool DEBUG_PRINT;
void ballPositionCallback(const ball_detector::circleSetStamped::ConstPtr &msg);
@ -107,6 +115,7 @@ class BallTracker
// z is the ball radius
geometry_msgs::Point ball_position_;
int tracking_status_;
bool use_head_scan_;
int count_not_found_;
bool on_tracking_;

View File

@ -42,6 +42,8 @@
#include "op3_demo/ball_tracker.h"
#include "op3_demo/ball_follower.h"
#include "robotis_math/robotis_linear_algebra.h"
#include "op3_action_module_msgs/IsRunning.h"
#include "robotis_controller_msgs/SyncWriteItem.h"
namespace robotis_op
{
@ -99,26 +101,33 @@ class SoccerDemo : public OPDemo
bool handleFallen(int fallen_status);
void playMotion(int motion_index);
void setRGBLED(int blue, int green, int red);
bool isActionRunning();
BallTracker ball_tracker_;
BallFollower ball_follower_;
ros::Publisher module_control_pub_;
ros::Publisher motion_index_pub_;
ros::Publisher rgb_led_pub_;
ros::Subscriber buttuon_sub_;
ros::Subscriber demo_command_sub_;
ros::Subscriber imu_data_sub_;
ros::ServiceClient is_running_client_;
std::map<int, std::string> id_joint_table_;
std::map<std::string, int> joint_id_table_;
bool is_grass_;
int wait_count_;
bool on_following_ball_;
bool on_following_ball_;
bool restart_soccer_;
bool start_following_;
bool stop_following_;
bool stop_fallen_check_;
int robot_status_;
int tracking_status_;
int stand_state_;
double present_pitch_;
};

View File

@ -1,9 +1,9 @@
<?xml version="1.0"?>
<!-- Launches an UVC camera, the ball detector and its visualization -->
<launch>
<!-- robotis op3 manager -->
<include file="$(find op3_manager)/launch/op3_manager.launch"/>
<include file="$(find op3_manager)/launch/op3_manager.launch"/>
<!-- Camera and Ball detector -->
<include file="$(find ball_detector)/launch/ball_detector_from_usb_cam.launch"/>

View File

@ -53,6 +53,7 @@ void goInitPose();
void playSound(const std::string &path);
void setLED(int led);
bool checkManagerRunning(std::string& manager_name);
void dxlTorqueChecker();
const int SPIN_RATE = 30;
const bool DEBUG_PRINT = false;
@ -60,6 +61,7 @@ const bool DEBUG_PRINT = false;
ros::Publisher init_pose_pub;
ros::Publisher play_sound_pub;
ros::Publisher led_pub;
ros::Publisher dxl_torque_pub;
std::string default_mp3_path = "";
int current_status = Ready;
@ -83,6 +85,7 @@ int main(int argc, char **argv)
init_pose_pub = nh.advertise<std_msgs::String>("/robotis/base/ini_pose", 0);
play_sound_pub = nh.advertise<std_msgs::String>("/play_sound_file", 0);
led_pub = nh.advertise<robotis_controller_msgs::SyncWriteItem>("/robotis/sync_write_item", 0);
dxl_torque_pub = nh.advertise<std_msgs::String>("/robotis/dxl_torque", 0);
ros::Subscriber buttuon_sub = nh.subscribe("/robotis/open_cr/button", 1, buttonHandlerCallback);
default_mp3_path = ros::package::getPath("op3_demo") + "/Data/mp3/";
@ -223,14 +226,17 @@ void buttonHandlerCallback(const std_msgs::String::ConstPtr& msg)
switch (desired_status)
{
case SoccerDemo:
dxlTorqueChecker();
playSound(default_mp3_path + "Start soccer demonstration.mp3");
break;
case VisionDemo:
dxlTorqueChecker();
playSound(default_mp3_path + "Start vision processing demonstration.mp3");
break;
case ActionDemo:
dxlTorqueChecker();
playSound(default_mp3_path + "Start motion demonstration.mp3");
break;
@ -313,3 +319,11 @@ bool checkManagerRunning(std::string& manager_name)
ROS_ERROR("Can't find op3_manager");
return false;
}
void dxlTorqueChecker()
{
std_msgs::String check_msg;
check_msg.data = "check";
dxl_torque_pub.publish(check_msg);
}

View File

@ -46,9 +46,9 @@ BallFollower::BallFollower()
kick_motion_index_(83),
CAMERA_HEIGHT(0.46),
NOT_FOUND_THRESHOLD(50),
MAX_FB_STEP(35.0 * 0.001),
MAX_FB_STEP(40.0 * 0.001),
MAX_RL_TURN(15.0 * M_PI / 180),
MIN_FB_STEP(5.0 * 0.001),
MIN_FB_STEP(0.0 * 0.001),
MIN_RL_TURN(5.0 * M_PI / 180),
UNIT_FB_STEP(1.0 * 0.001),
UNIT_RL_TURN(0.5 * M_PI / 180),
@ -177,7 +177,7 @@ void BallFollower::calcFootstep(double target_distance, double target_angle, dou
}
}
// x_angle : ball position (pan), y_angle : ball position (tilt)
// x_angle : ball position (pan), y_angle : ball position (tilt), ball_size : angle of ball radius
bool BallFollower::processFollowing(double x_angle, double y_angle, double ball_size)
{
ros::Time curr_time = ros::Time::now();

View File

@ -40,12 +40,14 @@ BallTracker::BallTracker()
FOV_WIDTH(26.4 * M_PI / 180),
FOV_HEIGHT(21.6 * M_PI / 180),
NOT_FOUND_THRESHOLD(50),
WAITING_THRESHOLD(5),
use_head_scan_(true),
count_not_found_(0),
on_tracking_(false),
current_ball_pan_(0),
current_ball_tilt_(0),
current_ball_bottom_(0),
tracking_status_(NotFound),
DEBUG_PRINT(false)
{
head_joint_pub_ = nh_.advertise<sensor_msgs::JointState>("/robotis/head_control/set_joint_states_offset", 0);
@ -112,13 +114,15 @@ void BallTracker::setUsingHeadScan(bool use_scan)
use_head_scan_ = use_scan;
}
bool BallTracker::processTracking()
int BallTracker::processTracking()
{
int tracking_status = Found;
if (on_tracking_ == false)
{
ball_position_.z = 0;
count_not_found_ = 0;
return false;
return NotFound;
}
// check ball position
@ -126,24 +130,56 @@ bool BallTracker::processTracking()
{
count_not_found_++;
if (count_not_found_ > NOT_FOUND_THRESHOLD)
if (count_not_found_ < WAITING_THRESHOLD)
{
if(tracking_status_ == Found || tracking_status_ == Waiting)
tracking_status = Waiting;
else
tracking_status = NotFound;
}
else if (count_not_found_ > NOT_FOUND_THRESHOLD)
{
scanBall();
count_not_found_ = 0;
tracking_status = NotFound;
}
return false;
else
{
tracking_status = NotFound;
}
}
else
{
count_not_found_ = 0;
}
// if ball is found
// convert ball position to desired angle(rad) of head
// ball_position : top-left is (-1, -1), bottom-right is (+1, +1)
// offset_rad : top-left(+, +), bottom-right(-, -)
double x_error = -atan(ball_position_.x * tan(FOV_WIDTH));
double y_error = -atan(ball_position_.y * tan(FOV_HEIGHT));
double x_error = 0.0, y_error = 0.0, ball_size = 0.0;
ball_position_.z = 0;
count_not_found_ = 0;
switch (tracking_status)
{
case NotFound:
tracking_status_ = tracking_status;
return tracking_status;
case Waiting:
x_error = current_ball_pan_ * 0.7;
y_error = current_ball_tilt_ * 0.7;
ball_size = current_ball_bottom_;
break;
case Found:
x_error = -atan(ball_position_.x * tan(FOV_WIDTH));
y_error = -atan(ball_position_.y * tan(FOV_HEIGHT));
ball_size = ball_position_.z;
break;
default:
break;
}
ROS_INFO_STREAM_COND(DEBUG_PRINT, "--------------------------------------------------------------");
ROS_INFO_STREAM_COND(DEBUG_PRINT, "Ball position : " << ball_position_.x << " | " << ball_position_.y);
@ -154,19 +190,20 @@ bool BallTracker::processTracking()
double delta_time = dur.nsec * 0.000000001 + dur.sec;
prev_time_ = curr_time;
// double p_gain = 0.75, d_gain = 0.05;
double p_gain = 0.7, d_gain = 0.05;
// double p_gain = 0.7, d_gain = 0.05;
double p_gain = 0.75, d_gain = 0.04;
double x_error_diff = (x_error - current_ball_pan_) / delta_time;
double y_error_diff = (y_error - current_ball_tilt_) / delta_time;
double x_error_target = x_error * p_gain + x_error_diff * d_gain;
double y_error_target = y_error * p_gain + y_error_diff * d_gain;
ROS_INFO_STREAM_COND(DEBUG_PRINT, "--------------------------------------------------------------");
ROS_INFO_STREAM_COND(DEBUG_PRINT, "error : " << (x_error * 180 / M_PI) << " | " << (y_error * 180 / M_PI));
ROS_INFO_STREAM_COND(DEBUG_PRINT,
ROS_INFO_STREAM_COND(
DEBUG_PRINT,
"error_diff : " << (x_error_diff * 180 / M_PI) << " | " << (y_error_diff * 180 / M_PI) << " | " << delta_time);
ROS_INFO_STREAM_COND(DEBUG_PRINT,
ROS_INFO_STREAM_COND(
DEBUG_PRINT,
"error_target : " << (x_error_target * 180 / M_PI) << " | " << (y_error_target * 180 / M_PI) << " | P : " << p_gain << " | D : " << d_gain);
// move head joint
@ -175,9 +212,13 @@ bool BallTracker::processTracking()
// args for following ball
current_ball_pan_ = x_error;
current_ball_tilt_ = y_error;
current_ball_bottom_ = -atan(ball_position_.z * tan(FOV_HEIGHT));
current_ball_bottom_ = ball_size;
return true;
ball_position_.z = 0;
//count_not_found_ = 0;
tracking_status_ = tracking_status;
return tracking_status;
}
void BallTracker::publishHeadJoint(double pan, double tilt)

View File

@ -48,6 +48,7 @@ SoccerDemo::SoccerDemo()
stop_fallen_check_(false),
robot_status_(Waited),
stand_state_(Stand),
tracking_status_(BallTracker::Waiting),
present_pitch_(0)
{
//init ros
@ -92,14 +93,17 @@ void SoccerDemo::setDemoDisable()
start_following_ = false;
stop_following_ = false;
stop_fallen_check_ = false;
tracking_status_ = BallTracker::Waiting;
}
void SoccerDemo::process()
{
// ball tracking
bool is_tracked;
int tracking_status;
is_tracked = ball_tracker_.processTracking();
tracking_status = ball_tracker_.processTracking();
// check to start
if (start_following_ == true)
@ -130,10 +134,26 @@ void SoccerDemo::process()
// ball following
if (on_following_ball_ == true)
{
if (is_tracked)
ball_follower_.processFollowing(ball_tracker_.getPanOfBall(), ball_tracker_.getTiltOfBall(), ball_tracker_.getBallSize());
else
ball_follower_.waitFollowing();
switch(tracking_status)
{
case BallTracker::Found:
ball_follower_.processFollowing(ball_tracker_.getPanOfBall(), ball_tracker_.getTiltOfBall(), 0.0);
if(tracking_status_ != tracking_status)
setRGBLED(0x1F, 0x1F, 0x1F);
break;
case BallTracker::NotFound:
ball_follower_.waitFollowing();
if(tracking_status_ != tracking_status)
setRGBLED(0, 0, 0);
break;
default:
break;
}
if(tracking_status != tracking_status_)
tracking_status_ = tracking_status;
}
// check fallen states
@ -171,7 +191,6 @@ void SoccerDemo::process()
{
wait_count_ -= 1;
}
}
void SoccerDemo::processThread()
@ -201,11 +220,14 @@ void SoccerDemo::callbackThread()
// subscriber & publisher
module_control_pub_ = nh.advertise<robotis_controller_msgs::JointCtrlModule>("/robotis/set_joint_ctrl_modules", 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);
buttuon_sub_ = nh.subscribe("/robotis/open_cr/button", 1, &SoccerDemo::buttonHandlerCallback, this);
demo_command_sub_ = nh.subscribe("/ball_tracker/command", 1, &SoccerDemo::demoCommandCallback, this);
imu_data_sub_ = nh.subscribe("/robotis/open_cr/imu", 1, &SoccerDemo::imuDataCallback, this);
is_running_client_ = nh.serviceClient<op3_action_module_msgs::IsRunning>("/robotis/action/is_running");
while (nh.ok())
{
ros::spinOnce();
@ -405,6 +427,14 @@ void SoccerDemo::imuDataCallback(const sensor_msgs::Imu::ConstPtr& msg)
void SoccerDemo::startSoccerMode()
{
setModuleToDemo("action_module");
usleep(10 * 1000);
playMotion(WalkingReady);
usleep(1500 * 1000);
setBodyModuleToDemo("walking_module");
usleep(10 * 1000);
@ -491,7 +521,10 @@ bool SoccerDemo::handleFallen(int fallen_status)
break;
}
usleep(500 * 1000);
while(isActionRunning() == true)
usleep(100 * 1000);
usleep(650 * 1000);
if (on_following_ball_ == true)
restart_soccer_ = true;
@ -510,4 +543,37 @@ void SoccerDemo::playMotion(int motion_index)
motion_index_pub_.publish(motion_msg);
}
void SoccerDemo::setRGBLED(int blue, int green, int red)
{
int led_full_unit = 0x1F;
int led_value = (blue & led_full_unit) << 10 | (green & led_full_unit) << 5 | (red & led_full_unit);
robotis_controller_msgs::SyncWriteItem syncwrite_msg;
syncwrite_msg.item_name = "LED_RGB";
syncwrite_msg.joint_name.push_back("open-cr");
syncwrite_msg.value.push_back(led_value);
rgb_led_pub_.publish(syncwrite_msg);
}
// check running of action
bool SoccerDemo::isActionRunning()
{
op3_action_module_msgs::IsRunning is_running_srv;
if (is_running_client_.call(is_running_srv) == false)
{
ROS_ERROR("Failed to get action status");
return true;
}
else
{
if (is_running_srv.response.is_running == true)
{
return true;
}
}
return false;
}
}

View File

@ -86,16 +86,10 @@ void VisionDemo::setDemoDisable()
void VisionDemo::process()
{
//bool is_tracked = face_tracker_.processTracking();
int tracking_status = face_tracker_.processTracking();
//if(is_tracking_ != is_tracked)
if(tracking_status_ != tracking_status)
{
// if(is_tracked == true)
// setRGBLED(0x1F, 0, 0);
// else
// setRGBLED(0x1F, 0x1F, 0);
switch(tracking_status)
{
case FaceTracker::Found: