ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I found a "reasonable" way of doing this. This method assumes that you built ros2 using colcon build --merge-install
but you can extrapolate this logic in case you used colcon build --symlink-install
1) Register the ROS2 install folder as a new_local_repository in the bazel WORKSPACE file by adding the following lines (located in the main nvidia isaac folder):
new_local_repository(
name = "ros2",
path = "(full path to the build folder) /ros2_foxy/install",
build_file = "(full path to the build folder) /ros2_foxy/install/BUILD",
)
2) Add a BUILD file inside the ros2/install folder with the following content: https://gist.github.com/dHofmeister/698c787cab9622c89b1a97ea878afac9
3) Add the depency of your isaac module to ros2:
isaac_cc_module( ... deps = ["@ros2//:ros2"],)
4) include the rclcpp library header in your isaac_cc_module:
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
4) Make sure you disable rclcpp's bind on the system SIGINT signal:
int argc = 1;
char const *const argv[] ={ "Bridge" };
rclcpp::InitOptions options{};
options.shutdown_on_sigint = false;
rclcpp::init(argc, argv, options);
ros_node = std::make_shared<MinimalPublisher>();
This code is implemented in the ::start()
function of your isaac_cc_module. make sure you initialise the ros_node variable in the node header std::shared_ptr<MinimalPublisher> ros_node;
.
You now have the ros_node class nested in the isaac_node class and can use them.
void Bridge::tick() {
geometry_msgs::msg::PoseStamped msg{};
ros_node->callback();
LOG_INFO("ping");
}
2 | No.2 Revision |
I found a "reasonable" way of doing this. This method assumes that you built ros2 using colcon build --merge-install
but you can extrapolate this logic in case you used colcon build --symlink-install
, you only need to modify the BUILD file for this.
1) Register the ROS2 install folder as a new_local_repository in the bazel WORKSPACE file by adding the following lines (located in the main nvidia isaac folder):
new_local_repository(
name = "ros2",
path = "(full path to the build folder) /ros2_foxy/install",
build_file = "(full path to the build folder) /ros2_foxy/install/BUILD",
)
2) Add a BUILD file inside the ros2/install folder with the following content: https://gist.github.com/dHofmeister/698c787cab9622c89b1a97ea878afac9
3) Add the depency of your isaac module to ros2:
isaac_cc_module( ... deps = ["@ros2//:ros2"],)
4) include the rclcpp library header in your isaac_cc_module:
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
4) Make sure you disable rclcpp's bind on the system SIGINT signal:signal as it conflicts with isaac's sigint handler:
int argc = 1;
char const *const argv[] ={ "Bridge" };
rclcpp::InitOptions options{};
options.shutdown_on_sigint = false;
rclcpp::init(argc, argv, options);
ros_node = std::make_shared<MinimalPublisher>();
This code is implemented in the ::start()
function of your isaac_cc_module. make sure you initialise the ros_node variable in the node header std::shared_ptr<MinimalPublisher> ros_node;
.
You now have the ros_node class nested in the isaac_node class and can use them.
void Bridge::tick() {
geometry_msgs::msg::PoseStamped msg{};
ros_node->callback();
LOG_INFO("ping");
}
3 | No.3 Revision |
I found a "reasonable" way of doing this. This method assumes that you built ros2 using colcon build --merge-install
but you can extrapolate this logic in case you used colcon build --symlink-install
, you only need to modify the BUILD file for this.
1) Register the ROS2 install folder as a new_local_repository in the bazel WORKSPACE file by adding the following lines (located in the main nvidia isaac folder):
new_local_repository(
name = "ros2",
path = "(full path to the build folder) /ros2_foxy/install",
build_file = "(full path to the build folder) /ros2_foxy/install/BUILD",
)
2) Add a BUILD file inside the ros2/install folder with the following content: https://gist.github.com/dHofmeister/698c787cab9622c89b1a97ea878afac9
3) Add the depency of your isaac module to ros2:
isaac_cc_module( ... deps = ["@ros2//:ros2"],)
4) include the rclcpp library header in your isaac_cc_module:
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
4) Make sure you disable rclcpp's bind on the system SIGINT signal as it conflicts with isaac's sigint handler:
int argc = 1;
char const *const argv[] ={ "Bridge" };
rclcpp::InitOptions options{};
options.shutdown_on_sigint = false;
rclcpp::init(argc, argv, options);
ros_node = std::make_shared<MinimalPublisher>();
This code is implemented in the ::start()
function of your isaac_cc_module. make sure you initialise the ros_node variable in the node header std::shared_ptr<MinimalPublisher> ros_node;
.
You now have the ros_node class nested in the isaac_node class and can use them.
void Bridge::tick() {
geometry_msgs::msg::PoseStamped msg{};
ros_node->callback();
LOG_INFO("ping");
}
}