-
Notifications
You must be signed in to change notification settings - Fork 5
ROS1ROS2
Ernő Horváth edited this page Dec 28, 2022
·
4 revisions
ROS1 | ROS2 |
---|---|
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "std_msgs/UInt8.h"
#include "std_msgs/Float64.h"
#include "nav_msgs/Odometry.h"
#include "sensor_msgs/NavSatFix.h"
#include "sensor_msgs/NavSatStatus.h"
#include "sensor_msgs/Imu.h"
#include "sensor_msgs/MagneticField.h"
#include "sensor_msgs/TimeReference.h"
#include "geometry_msgs/Vector3.h"
#include "geometry_msgs/PoseStamped.h"
#include "tf2/LinearMath/Quaternion.h" |
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_msgs/msg/u_int8.hpp"
#include "std_msgs/msg/float64.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "sensor_msgs/msg/nav_sat_fix.hpp"
#include "sensor_msgs/msg/nav_sat_status.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include "sensor_msgs/msg/magnetic_field.hpp"
#include "sensor_msgs/msg/time_reference.hpp"
#include "geometry_msgs/msg/vector3.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "tf2/LinearMath/Quaternion.h"
|
ROS1 | ROS2 |
---|---|
n_private.param<std::string>
("ip_address", tcp_ip_addr, "192.168.0.222");
n_private.param<int>("port", tcp_ip_port, 55555);
n_private.param<std::string>("gps_receiver_frame_id",
gps_receiver_frame_id, "duro_link");
n_private.param<std::string>("imu_frame_id",
imu_frame_id, gps_receiver_frame_id);
n_private.param<std::string>("utm_frame_id",
utm_frame_id, "utm");
n_private.param<std::string>("z_coord_ref_switch",
z_coord_ref_switch, "zero");
n_private.param<std::string>("orientation_source",
orientation_source, "gps");
n_private.param<bool>("euler_based_orientation",
euler_based_orientation, true);
|
node->declare_parameter<std::string>
("ip_address", "192.168.0.222");
node->declare_parameter<int>("port", 55555);
node->declare_parameter<std::string>
("gps_receiver_frame", "duro");
node->declare_parameter<std::string>("imu_frame","duro");
node->declare_parameter<std::string>
("utm_frame", "map");
node->declare_parameter<std::string>
("orientation_source", "gps");
node->declare_parameter<std::string>
("z_coord_ref_switch", "orig");
node->declare_parameter<bool>
("euler_based_orientation", true);
node->get_parameter("ip_address", tcp_ip_addr);
node->get_parameter("port", tcp_ip_port);
node->get_parameter("gps_receiver_frame",
gps_receiver_frame);
node->get_parameter("imu_frame", imu_frame);
node->get_parameter("utm_frame", utm_frame);
node->get_parameter("orientation_source",
orientation_source);
node->get_parameter("z_coord_ref_switch",
z_coord_ref_switch);
node->get_parameter("euler_based_orientation",
euler_based_orientation);
|
ROS1 | ROS2 |
---|---|
|
|
English
- Wiki home
ROS2
migration- Version handling processes
- Xavier installation
- Startup Nissan Leaf
- Debug ROS
- Autoware universe
- Autoware msgs
- How to open rosbag files
ROS 2
humble jeston dockerROS 2
DDSROS 2
joystick WSL
Hungarian
- Topics
- Transforms, frames
- Cheatsheet 🔥
- SSH no password
- Boot, systemd
- Diagnostics
- NDT basics
- NDT comparison
- CUDA install
- Szimulátor indítása parkolási feladathoz
- WSL-el kapcsolatos hasznos infók
- GPS-based pointcloud map
- Rviz video
- LIDAR detekció topicjai
Further: