Skip to content

Fw2.4 #11

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

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
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
4 changes: 2 additions & 2 deletions launch/decoder.launch
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@

<!-- input topics -->
<remap from="~metadata" to="$(arg driver_ns)/metadata"/>
<remap from="~os_config" to="$(arg driver_ns)/os_config"/>
<remap from="~get_metadata" to="$(arg driver_ns)/get_metadata"/>
<remap from="~imu_packets" to="$(arg driver_ns)/imu_packets"/>
<remap from="~lidar_packets" to="$(arg driver_ns)/lidar_packets"/>

Expand All @@ -76,4 +76,4 @@
<remap from="~range" to="range"/>
<remap from="~signal" to="signal"/>
</node>
</launch>
</launch>
15 changes: 1 addition & 14 deletions launch/driver.launch
Original file line number Diff line number Diff line change
Expand Up @@ -21,17 +21,4 @@
<param name="~/imu_port" value="$(arg imu_port)"/>
<param name="~/metadata" value="$(arg metadata)"/>
</node>

<!-- Get rid of this later -->
<node pkg="ouster_ros" type="os_cloud_node" name="os_cloud_node" output="screen" required="true">
<remap from="~/os_config" to="/os_node/os_config"/>
<remap from="~/lidar_packets" to="/os_node/lidar_packets"/>
<remap from="~/imu_packets" to="/os_node/imu_packets"/>
<param name="~/tf_prefix" value="$(arg tf_prefix)"/>
</node>

<!-- <node pkg="ouster_ros" name="img_node" type="img_node" output="screen" required="true">
<remap from="~/os_config" to="/os_node/os_config"/>
<remap from="~/points" to="/os_cloud_node/points"/>
</node> -->
</launch>
</launch>
10 changes: 5 additions & 5 deletions src/decoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <tf2_ros/static_transform_broadcaster.h>

#include "lidar.h"
#include "ouster_ros/OSConfigSrv.h"
#include "ouster_ros/GetMetadata.h"
#include "ouster_ros/PacketMsg.h"

namespace ouster_decoder {
Expand Down Expand Up @@ -138,7 +138,7 @@ void Decoder::InitParams() {
void Decoder::InitOuster() {
ROS_INFO_STREAM("=== Initializing Ouster Decoder ===");
// wait for service
auto client = pnh_.serviceClient<ouster_ros::OSConfigSrv>("os_config");
auto client = pnh_.serviceClient<ouster_ros::GetMetadata>("get_metadata");

// NOTE: it is possible that in replay mode, the service was shutdown and
// re-advertised. If the client call is too soon, then we risk getting the old
Expand All @@ -151,10 +151,10 @@ void Decoder::InitOuster() {

client.waitForExistence();

ouster_ros::OSConfigSrv cfg{};
ouster_ros::GetMetadata srv{};
// Initialize everything if service call is successful
if (client.call(cfg)) {
InitModel(cfg.response.metadata);
if (client.call(srv)) {
InitModel(srv.response.metadata);
InitScan(model_);
SendTransform(model_);
} else {
Expand Down
22 changes: 10 additions & 12 deletions src/driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
*/

// This is a modified version of ouster_ros/os_node.cpp
// It is intended to have the same behavior as os_node.
// It is intended to have the same behavior as os_node.
// The only difference is that we also advertise the metadata message.

#include <ros/ros.h>
Expand All @@ -23,14 +23,12 @@
#include <sstream>
#include <string>

// #include "ouster/build.h"
#include "ouster/types.h"
#include "ouster_ros/OSConfigSrv.h"
#include "ouster_ros/GetMetadata.h"
#include "ouster_ros/PacketMsg.h"
#include "ouster_ros/ros.h"
#include "ouster_ros/os_ros.h"

using PacketMsg = ouster_ros::PacketMsg;
using OSConfigSrv = ouster_ros::OSConfigSrv;
using OsGetMetadata = ouster_ros::GetMetadata;
namespace sensor = ouster::sensor;

// fill in values that could not be parsed from metadata
Expand Down Expand Up @@ -130,9 +128,9 @@ void advertise_service(ros::NodeHandle& nh,
srv.getService().c_str());
srv.shutdown();
}
srv = nh.advertiseService<OSConfigSrv::Request, OSConfigSrv::Response>(
"os_config",
[metadata](OSConfigSrv::Request&, OSConfigSrv::Response& res) {
srv = nh.advertiseService<OsGetMetadata::Request, OsGetMetadata::Response>(
"get_metadata",
[metadata](OsGetMetadata::Request&, OsGetMetadata::Response& res) {
if (metadata.empty()) return false;
res.metadata = metadata;
return true;
Expand Down Expand Up @@ -279,9 +277,9 @@ int main(int argc, char** argv) {
pub_meta.publish(meta_msg);
ROS_INFO("Publish metadata to %s", pub_meta.getTopic().c_str());

srv = nh.advertiseService<OSConfigSrv::Request, OSConfigSrv::Response>(
"os_config",
[metadata](OSConfigSrv::Request&, OSConfigSrv::Response& res) {
srv = nh.advertiseService<OsGetMetadata::Request, OsGetMetadata::Response>(
"get_metadata",
[metadata](OsGetMetadata::Request&, OsGetMetadata::Response& res) {
if (metadata.empty()) return false;
res.metadata = metadata;
return true;
Expand Down
2 changes: 1 addition & 1 deletion src/lidar.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <sensor_msgs/Image.h>
#include <sensor_msgs/PointCloud2.h>

#include "ouster_ros/ros.h"
#include "ouster_ros/os_ros.h"

namespace ouster_decoder {

Expand Down