Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Send TM command after receiving QT response #91

Merged
merged 4 commits into from
Mar 24, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 1 addition & 2 deletions include/urg_stamped/urg_stamped.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@ class UrgStampedNode
ros::Publisher pub_scan_;
ros::Timer timer_sync_;
ros::Timer timer_delay_estim_;
ros::Timer timer_try_tm_;

sensor_msgs::LaserScan msg_base_;
uint32_t step_min_;
Expand All @@ -61,6 +60,7 @@ class UrgStampedNode

bool publish_intensity_;

bool try_tm_;
boost::posix_time::ptime time_tm_request;
std::list<ros::Duration> communication_delays_;
std::list<ros::Time> device_time_origins_;
Expand Down Expand Up @@ -141,7 +141,6 @@ class UrgStampedNode

void timeSync(const ros::TimerEvent& event = ros::TimerEvent());
void delayEstimation(const ros::TimerEvent& event = ros::TimerEvent());
void tryTM(const ros::TimerEvent& event = ros::TimerEvent());

void errorCountIncrement(const std::string& status);

Expand Down
17 changes: 8 additions & 9 deletions src/urg_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,6 @@ void UrgStampedNode::cbTM(
return;
}

timer_try_tm_.stop();
switch (echo_back[2])
{
case '0':
Expand Down Expand Up @@ -357,6 +356,12 @@ void UrgStampedNode::cbQT(
}

ROS_DEBUG("Scan data stopped");

if (try_tm_)
{
try_tm_ = false;
scip_->sendCommand("TM0");
}
}
void UrgStampedNode::cbRB(
const boost::posix_time::ptime& time_read,
Expand Down Expand Up @@ -388,15 +393,8 @@ void UrgStampedNode::delayEstimation(const ros::TimerEvent& event)
{
timer_sync_.stop();
ROS_DEBUG("Starting communication delay estimation");
try_tm_ = true;
scip_->sendCommand("QT");
timer_try_tm_ = nh_.createTimer(
ros::Duration(0.05),
&UrgStampedNode::tryTM, this);
}
void UrgStampedNode::tryTM(const ros::TimerEvent& event)
{
scip_->sendCommand("QT");
scip_->sendCommand("TM0");
}

void UrgStampedNode::errorCountIncrement(const std::string& status)
Expand Down Expand Up @@ -553,6 +551,7 @@ void UrgStampedNode::spin()
boost::bind(&scip2::Connection::spin, device_.get()));
ros::spin();
timer_sync_.stop();
try_tm_ = false;
scip_->sendCommand("QT");
device_->stop();
}
Expand Down