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

add robustness to missing inputbag path #2

Merged
merged 1 commit into from
Sep 14, 2024
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
2 changes: 1 addition & 1 deletion launch/replay_packets.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<launch>


<arg name="input_rosbag_path" default="/home/tutuna/box_ws/src/grand_tour_box/box_drivers/novatel_oem7_driver/src/novatel_oem7_driver/data/2024-08-14-10-45-39_nuc_hesai_1.bag"/>
<arg name="input_rosbag_path" default=""/>

<param name="/use_sim_time" value="true"/>
<arg name="node_start_delay" default="2.0" />
Expand Down
1 change: 1 addition & 0 deletions launch/start.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
<launch>
<node pkg="hesai_ros_driver" name="hesai_ros_driver_node" type="hesai_ros_driver_node" output="screen">
<param name="config_path" type="string" value= "$(find hesai_ros_driver)/config/config.yaml"/>
<param name="input_rosbag_path" type="string" value=""/>
</node>
<!-- rviz -->
<node pkg="rviz" name="rviz" type="rviz" args="-d '$(find hesai_ros_driver)/rviz/rviz.rviz'" required="true"/>
Expand Down
123 changes: 59 additions & 64 deletions src/manager/source_driver_ros1.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -265,10 +265,15 @@ inline void SourceDriver::Start()
std::this_thread::sleep_for(std::chrono::milliseconds(50));

input_rosbag_path_ = driver_ptr_->inputRosbagPath_;
if (input_rosbag_path_ != ""){
if (!(save_replayed_topics_to_rosbag_))
{
ROS_WARN("[HesaiXT32] Replay mode is off.");
return;
}

if ( (input_rosbag_path_ != "") && (save_replayed_topics_to_rosbag_)){

ROS_WARN_STREAM("driver_ptr_->inputRosbagPath_: " << driver_ptr_->inputRosbagPath_);

ROS_WARN_STREAM("Input rosbag path: " << input_rosbag_path_);

// We need to do a dry-run on the rosbag to get the end time of the rosbag.
Expand All @@ -278,79 +283,69 @@ inline void SourceDriver::Start()
viewtopics.push_back("/gt_box/hesai/packets");

{

rosbag::View view(inputBag, rosbag::TopicQuery(viewtopics));
ros::Duration rosbag_duration = view.getEndTime() - view.getBeginTime();

// ros::Time custom_start =
// rosbag::View(bag).getBeginTime() + ros::Duration(view.getBeginTime());
// ros::Time custom_t_end =
// duration >= 0 ? custom_start + ros::Duration(duration) : ros::TIME_MAX;

// // customView.addQuery(customView.getConnections(), rosbag::TopicQuery::Options());
// // customView.setQueryOptions(rosbag::TopicQuery::Options(rosbag::TopicQuery::REVERSE));
// auto lastMessageIter = view.end();
// ros::Time lastMsgTime = lastMessageIter->getTime();
// ROS_WARN_STREAM("Last Msg time in the bag is: " << lastMsgTime.toSec() << " s");

// for (rosbag::View::iterator it = view.end(); it != view.begin(); --it) {
// rosbag::View::iterator it2 = view.end();
// ros::Time lastMsgTime = it2->getTime();
// ROS_WARN_STREAM("lastMsgTime: " << lastMsgTime.toSec() << " s");

// if (fp != NULL) {
// dataset->push_back(*fp);
rosbag::View view(inputBag, rosbag::TopicQuery(viewtopics));
ros::Duration rosbag_duration = view.getEndTime() - view.getBeginTime();

// ros::Time custom_start =
// rosbag::View(bag).getBeginTime() + ros::Duration(view.getBeginTime());
// ros::Time custom_t_end =
// duration >= 0 ? custom_start + ros::Duration(duration) : ros::TIME_MAX;

// // customView.addQuery(customView.getConnections(), rosbag::TopicQuery::Options());
// // customView.setQueryOptions(rosbag::TopicQuery::Options(rosbag::TopicQuery::REVERSE));
// auto lastMessageIter = view.end();
// ros::Time lastMsgTime = lastMessageIter->getTime();
// ROS_WARN_STREAM("Last Msg time in the bag is: " << lastMsgTime.toSec() << " s");

// for (rosbag::View::iterator it = view.end(); it != view.begin(); --it) {
// rosbag::View::iterator it2 = view.end();
// ros::Time lastMsgTime = it2->getTime();
// ROS_WARN_STREAM("lastMsgTime: " << lastMsgTime.toSec() << " s");

// if (fp != NULL) {
// dataset->push_back(*fp);
// }
// }
// }


totalNumberOfPackets_ = view.size();

ROS_WARN_STREAM("ROS bag begin time: " << view.getBeginTime().toSec() << " ROS bag end time: "
<< view.getEndTime().toSec() << " s " << "Duration: " << rosbag_duration.toSec() << " s");


bagStartTime_ = view.getBeginTime();
bagEndTime_ = view.getEndTime();
duration_ = bagEndTime_.toNSec() - bagStartTime_.toNSec();
totalNumberOfPackets_ = view.size();

ROS_WARN_STREAM("ROS bag begin time: " << view.getBeginTime().toSec() << " ROS bag end time: "
<< view.getEndTime().toSec() << " s " << "Duration: " << rosbag_duration.toSec() << " s");

bagStartTime_ = view.getBeginTime();
bagEndTime_ = view.getEndTime();
duration_ = bagEndTime_.toNSec() - bagStartTime_.toNSec();


auto it = view.begin();
// size_t dec_pointer = view.size()-1;
// auto last_it = view.crbegin();
rosbag::View::iterator last_item;
rosbag::View::iterator lastlast_item;
while (it != view.end())
{
last_item = it++;

auto it = view.begin();
// size_t dec_pointer = view.size()-1;
// auto last_it = view.crbegin();
rosbag::View::iterator last_item;
rosbag::View::iterator lastlast_item;
while (it != view.end())
{
last_item = it++;
if (it == view.end())
{
break;
}else{
lastlast_item = last_item;
}
}

if (it == view.end())
{
break;
}else{
lastlast_item = last_item;
}
}
{
// last_item = --it;
// rosbag::View customView(inputBag, rosbag::TopicQuery(viewtopics));
// rosbag::View::iterator it2 = customView.end();
lastPossibleMsgTime_ = lastlast_item->getTime();
// lastlast_item = (last_item+(dec_pointer--))
// ROS_WARN_STREAM("Last Msg time in the bag is: " << lastMsgTime.toNSec() << " s");

{
// last_item = --it;
// rosbag::View customView(inputBag, rosbag::TopicQuery(viewtopics));
// rosbag::View::iterator it2 = customView.end();
lastPossibleMsgTime_ = lastlast_item->getTime();
// lastlast_item = (last_item+(dec_pointer--))
// ROS_WARN_STREAM("Last Msg time in the bag is: " << lastMsgTime.toNSec() << " s");
}

}



}



}else{
ROS_ERROR_STREAM("Input rosbag path is empty. Exiting...");
raise(SIGINT);
Expand Down Expand Up @@ -540,7 +535,7 @@ inline sensor_msgs::PointCloud2 SourceDriver::ToRosMsg(const LidarDecodedFrame<L
outputBag.write("/gt_box/hesai/points_last", lastPointStamp_, ros_msg_last);
}

ros::Time now = ros::Time::now();
// ros::Time now = ros::Time::now();
// ROS_WARN_STREAM("Time diff left: " << lastPossibleMsgTime_.toNSec() - latestCloudStamp_.toNSec());
// ROS_WARN_STREAM("Time diff NOW: " << lastPossibleMsgTime_.toNSec() - now.toNSec());

Expand Down