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

Update/launch file #90

Merged
merged 2 commits into from
Oct 11, 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
99 changes: 50 additions & 49 deletions orange_bringup/launch/orange_robot.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,15 @@
<arg name="cmd_rpm_topic" default="/vel/cmd_rpm"/>
<arg name="cmd_deg_topic" default="/pos/cmd_deg"/>
<arg name="cmd_dist_topic" default="/pos/cmd_dist"/>
<arg name="hokuyo_scan_topic" default="/hokuyo_scan"/>
<arg name="odom_topic" default="/odom"/>
<arg name="imu_topic" default="/livox/imu"/>
<arg name="fusion_odom_topic" default="/fusion/odom"/>
<arg name="ekf_publish_TF" default="false"/>
<arg name="hokuyo_scan_topic" default="/hokuyo_scan"/>
<arg name="velodyne_scan_topic" default="/velodyne_scan"/>
<arg name="velodyne_points_topic" default="/velodyne_points"/>
<arg name="livox_scan_topic" default="/livox_scan"/>
<arg name="livox_points_topic" default="/livox_points"/>
<arg name="velodyne_points_topic" default="/velodyne_points"/>
<arg name="merged_cloud_topic" default="/merged_cloud"/>
<arg name="merged_scan_topic" default="/merged_scan"/>
<arg name="xacro_file_path" default="$(find-pkg-share orange_description)/xacro/orange_robot.xacro"/>
Expand All @@ -35,12 +36,47 @@
<node pkg="joint_state_publisher" exec="joint_state_publisher">
<param name="robot_description" value="$(command 'xacro $(var xacro_file_path)')"/>
</node>
<!-- robot_localization
<include file="$(find-pkg-share orange_sensor_tools)/launch/localization.launch.xml">
<!-- motor_driver_node -->
<node pkg="orange_bringup" exec="motor_driver_node" output="screen">
<param from="$(var motor_driver_config_file_path)"/>
<param name="port" value="/dev/ZLAC8015D"/>
<param name="control_mode" value="$(var control_mode)"/>
<param name="debug" value="$(var debug_motor)"/>
<param name="twist_cmd_vel_topic" value="$(var twist_cmd_vel_topic)"/>
<param name="cmd_vel_topic" value="$(var cmd_vel_topic)"/>
<param name="cmd_rpm_topic" value="$(var cmd_rpm_topic)"/>
<param name="cmd_deg_topic" value="$(var cmd_deg_topic)"/>
<param name="cmd_dist_topic" value="$(var cmd_dist_topic)"/>
<param name="publish_TF" value="$(var publish_TF)"/>
<param name="TF_header_frame" value="odom"/>
<param name="TF_child_frame" value="base_footprint"/>
<param name="publish_odom" value="$(var publish_odom)"/>
<param name="odom_header_frame" value="odom"/>
<param name="odom_child_frame" value="base_footprint"/>
</node>
<!-- estop -->
<node pkg="estop_ros" exec="cmd_vel_override_node" output="screen">
<param name="port" value="/dev/sensors/estop"/>
<param name="baudrate" value="115200"/>
<param name="time_out" value="500"/>
<param name="serial_interval" value="0.01"/>
<remap from="/estop/state" to="/estop"/>
</node>
<!-- imu -->
<include file="$(find-pkg-share icm_20948)/launch/run.launch.xml">
<arg name="port" value="/dev/sensors/imu"/>
<arg name="time_out" value="0.5"/>
<arg name="baudrate" value="115200"/>
<arg name="imu_topic" value="imu"/>
<arg name="frame_id" value="imu_link"/>
<arg name="debug" value="$(var debug_imu)"/>
</include>
<!-- robot_localization -->
<!--<include file="$(find-pkg-share orange_sensor_tools)/launch/localization.launch.xml">
<arg name="odom_in" value="$(var odom_topic)"/>
<arg name="imu_in" value="$(var imu_topic)"/>
<arg name="fusion_odom_out" value="$(var fusion_odom_topic)"/>
</include> -->
</include>-->
<!-- GPSposition_publisher -->
<!-- initial heading:housei nakaniwa=179.169287 tsukuba= 291.09504 -->
<node pkg="orange_bringup" exec="fix_to_GPSodom" output="screen">
Expand All @@ -63,26 +99,16 @@
</node>
<!-- ekf_myself -->
<node pkg="orange_bringup" exec="ekf_myself" output="screen">
<param name="ekf_publish_TF" value="True"/>
</node>
<!-- motor_driver_node -->
<node pkg="orange_bringup" exec="motor_driver_node" output="screen">
<param from="$(var motor_driver_config_file_path)"/>
<param name="port" value="/dev/ZLAC8015D"/>
<param name="control_mode" value="$(var control_mode)"/>
<param name="debug" value="$(var debug_motor)"/>
<param name="twist_cmd_vel_topic" value="$(var twist_cmd_vel_topic)"/>
<param name="cmd_vel_topic" value="$(var cmd_vel_topic)"/>
<param name="cmd_rpm_topic" value="$(var cmd_rpm_topic)"/>
<param name="cmd_deg_topic" value="$(var cmd_deg_topic)"/>
<param name="cmd_dist_topic" value="$(var cmd_dist_topic)"/>
<param name="publish_TF" value="$(var publish_TF)"/>
<param name="TF_header_frame" value="odom"/>
<param name="TF_child_frame" value="base_footprint"/>
<param name="publish_odom" value="$(var publish_odom)"/>
<param name="odom_header_frame" value="odom"/>
<param name="odom_child_frame" value="base_footprint"/>
<param name="ekf_publish_TF" value="$(var ekf_publish_TF)"/>
</node>
<!-- hokuyo -->
<!--<node pkg="urg_node" exec="urg_node_driver">
<param name="serial_port" value="/dev/sensors/hokuyo_urg"/>
<param name="laser_frame_id" value="hokuyo_link"/>
<param name="angle_max" value="1.22"/>
<param name="angle_min" value="-1.22"/>
<remap from="/scan" to="/hokuyo_scan"/>
</node>-->
<!-- velodyne -->
<!--<node pkg="velodyne_driver" exec="velodyne_driver_node">
<param name="device_ip" value=""/>
Expand Down Expand Up @@ -114,31 +140,6 @@
<node pkg="livox_to_pointcloud2" exec="livox_to_pointcloud2_node">
<remap from="/livox_pointcloud" to="/livox/lidar"/>
</node>
<!-- hokuyo -->
<!--<node pkg="urg_node" exec="urg_node_driver">
<param name="serial_port" value="/dev/sensors/hokuyo_urg"/>
<param name="laser_frame_id" value="hokuyo_link"/>
<param name="angle_max" value="1.22"/>
<param name="angle_min" value="-1.22"/>
<remap from="/scan" to="/hokuyo_scan"/>
</node>-->
<!-- imu -->
<!--<include file="$(find-pkg-share icm_20948)/launch/run.launch.xml">
<arg name="port" value="/dev/sensors/imu"/>
<arg name="time_out" value="0.5"/>
<arg name="baudrate" value="115200"/>
<arg name="imu_topic" value="imu"/>
<arg name="frame_id" value="imu_link"/>
<arg name="debug" value="$(var debug_imu)"/>
</include>-->
<!-- estop -->
<node pkg="estop_ros" exec="cmd_vel_override_node" output="screen">
<param name="port" value="/dev/sensors/estop"/>
<param name="baudrate" value="115200"/>
<param name="time_out" value="500"/>
<param name="serial_interval" value="0.01"/>
<remap from="/estop/state" to="/estop"/>
</node>
<!-- ground_segmentation >
<include file="$(find-pkg-share orange_sensor_tools)/launch/ground_segmentation.launch.xml">
<arg name="config_file_path" value="$(find-pkg-share orange_sensor_tools)/config/ground_segmentation.yaml"/>
Expand Down
4 changes: 2 additions & 2 deletions orange_bringup/orange_bringup/ekf_myself.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,9 @@ def __init__(self):
self.sub_b = self.create_subscription(
Odometry, '/odom_CLAS_movingbase', self.sensor_b_callback, 10)

self.declare_parameter("publish_TF", False)
self.declare_parameter("ekf_publish_TF", False)
self.ekf_publish_TF = self.get_parameter(
"publish_TF").get_parameter_value().bool_value
"ekf_publish_TF").get_parameter_value().bool_value

self.t = TransformStamped()
self.br = tf2_ros.TransformBroadcaster(self)
Expand Down
Loading