Merge branch 'PD_dev' into 'master'

Pd dev

See merge request westonrobot/ros/scout_base!3
This commit is contained in:
Ruixiang Du
2020-09-07 10:38:29 +00:00
30 changed files with 2457 additions and 47 deletions

View File

@@ -45,12 +45,22 @@ Nvidia Jeston TX2/Xavier/XavierNX have CAN controller(s) integrated in the main
$ roslaunch scout_bringup scout_minimal.launch $ roslaunch scout_bringup scout_minimal.launch
``` ```
The [scout_bringup scout_minimal.launch](scout_bringup/launch/scout_minimal.launch) has 4 parameters:
- port_name: Determines port to communicate with robot. Default = "can0"
- simulated_robot: Indicates if launching with a simulation. Default = "false"
- model_xacro: Indicates the target .xacro file for the publishing of tf frames. Default = [scout_v2.xacro](scout_base/description/scout_v2.xacro)
- odom_topic_name: Sets the name of the topic which calculated odometry is published. Defaults = "odom"
or (if you're using a serial port) or (if you're using a serial port)
``` ```
$ roslaunch scout_bringup scout_minimal_uart.launch $ roslaunch scout_bringup scout_minimal_uart.launch
``` ```
- Similarly, the [scout_bringup_uart.launch](scout_bringup/launch/scout_minimal_uart.launch) has the same 4 parameters with port_name default = "/dev/ttyUSB0".
* Start the keyboard tele-op node * Start the keyboard tele-op node
``` ```
@@ -60,3 +70,22 @@ Nvidia Jeston TX2/Xavier/XavierNX have CAN controller(s) integrated in the main
**SAFETY PRECAUSION**: **SAFETY PRECAUSION**:
The default command values of the keyboard teleop node are high, make sure you decrease the speed commands before starting to control the robot with your keyboard! Have your remote controller ready to take over the control whenever necessary. The default command values of the keyboard teleop node are high, make sure you decrease the speed commands before starting to control the robot with your keyboard! Have your remote controller ready to take over the control whenever necessary.
## Update the package for your customized robot
A brief overview of how to use this ROS package for your custom setup of the scout platform is described in this segment. A detailed example of such applications can be found in the [scout_navigation]() repository.
### Additional Sensors
It's likely that you may want to add additional sensors to the scout mobile platform, such as a Lidar for navigation. In such cases, a new .xacro file needs to be created to describe the relative pose of the new sensor with respect to the robot base, so that the sensor frame can be reflected in the robot tf tree.
A [sample](samples/scout_v2_nav.xacro) .xacro file is present in this repository. The base .xacro file of an empty scout platform is included in this sample, and additional links are defined.
The nodes in this ROS package are made to handle only the control of the scout base and publishing of the status. Additional nodes may need to be created by the user to handle the sensors.
### Alternative Odometry Calculation
Another frequent usage would be using sensor fusion of an IMU. In such a scenario, the odometry calculated by this package would likely be needed to publish under a custom name, instead of "/odom". Therefore, the name of the topic can be set by using
```
$ scout_bringup scout_minimal.launch odom_topic_name:="<custom_name>"
```

View File

@@ -0,0 +1,48 @@
<?xml version="1.0"?>
<robot name="scout_v2"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find scout_base)/description/scout_v2.xacro" />
<!-- For testing, hang the robot up in the air -->
<!-- <link name="world" />
<joint name="world_to_base_link=" type="fixed">
<origin xyz="0 0 0.5" rpy="0 0 0" />
<parent link="world"/>
<child link="base_link"/>
</joint> -->
<link name="imu_link">
<visual>
<origin xyz="0.0 0.0 0.0" />
<geometry>
<cylinder length="0.03" radius="0.02" />
</geometry>
<material name="red" />
</visual>
</link>
<joint name="imu_joint" type="fixed">
<parent link="base_link" />
<child link="imu_link" />
<origin xyz="0.32 0.0 0.18" rpy="0 0 0" />
</joint>
<link name="laser">
<visual>
<origin xyz="0.0 0.0 0.0" />
<geometry>
<cylinder length="0.03" radius="0.02" />
</geometry>
<material name="red" />
</visual>
</link>
<joint name="base_laser_joint" type="fixed">
<parent link="base_link" />
<child link="laser" />
<origin xyz="0.0 0.0 0.65" rpy="0 0 0" />
</joint>
</robot>

View File

@@ -30,6 +30,7 @@ public:
std::string odom_frame_; std::string odom_frame_;
std::string base_frame_; std::string base_frame_;
std::string odom_topic_name_;
bool simulated_robot_ = false; bool simulated_robot_ = false;
int sim_control_rate_ = 50; int sim_control_rate_ = 50;

View File

@@ -12,11 +12,15 @@
<arg name="port_name" default="can0" /> <arg name="port_name" default="can0" />
<arg name="simulated_robot" default="false" /> <arg name="simulated_robot" default="false" />
<arg name ="odom_topic_name" default = "odom"/>
<node name="scout_base_node" pkg="scout_base" type="scout_base_node" output="screen"> <node name="scout_base_node" pkg="scout_base" type="scout_base_node" output="screen">
<param name="port_name" type="string" value="$(arg port_name)" /> <param name="port_name" type="string" value="$(arg port_name)" />
<param name="simulated_robot" type="bool" value="$(arg simulated_robot)" /> <param name="simulated_robot" type="bool" value="$(arg simulated_robot)" />
<param name="odom_frame" type="string" value="odom" /> <param name="odom_frame" type="string" value="odom" />
<param name="base_frame" type="string" value="base_link" /> <param name="base_frame" type="string" value="base_link" />
<param name = "odom_topic_name" type="string" value="$(arg odom_topic_name)" />
</node> </node>
</launch> </launch>

View File

@@ -1,22 +0,0 @@
<launch>
<!--
The robot can be controlled either through CAN bus or UART port. Make sure the hardware
interface is set up correctly before attempting to connect to the robot.
You only need to specify the port name, such as "can0", "/dev/ttyUSB0". The port should
operate with the following configuration:
* CAN bus: 500k
* UART: 115200, Parity None, 8-bit Data, 1 Stop Bit
-->
<arg name="simulated_robot" default="true" />
<arg name="control_rate" default="50" />
<node name="scout_base_node" pkg="scout_base" type="scout_base_node" output="screen">
<param name="simulated_robot" type="bool" value="$(arg simulated_robot)" />
<param name="control_rate" type="int" value="$(arg control_rate)" />
<param name="odom_frame" type="string" value="odom" />
<param name="base_frame" type="string" value="base_link" />
</node>
</launch>

View File

@@ -1,6 +0,0 @@
<launch>
<param name="robot_description" textfile="$(find scout_base)/urdf/agilex_scout.urdf" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" required="true" args="-d $(find scout_viz)/rviz/scout_model.rviz" />
</launch>

View File

@@ -27,6 +27,8 @@ int main(int argc, char **argv) {
private_node.param<bool>("simulated_robot", messenger.simulated_robot_, private_node.param<bool>("simulated_robot", messenger.simulated_robot_,
false); false);
private_node.param<int>("control_rate", messenger.sim_control_rate_, 50); private_node.param<int>("control_rate", messenger.sim_control_rate_, 50);
private_node.param<std::string>("odom_topic_name", messenger.odom_topic_name_,
std::string("odom"));
if (!messenger.simulated_robot_) { if (!messenger.simulated_robot_) {
// connect to robot and setup ROS subscription // connect to robot and setup ROS subscription

View File

@@ -13,16 +13,18 @@
#include "scout_msgs/ScoutStatus.h" #include "scout_msgs/ScoutStatus.h"
namespace westonrobot { namespace westonrobot {
ScoutROSMessenger::ScoutROSMessenger(ros::NodeHandle *nh) ScoutROSMessenger::ScoutROSMessenger(ros::NodeHandle *nh)
: scout_(nullptr), nh_(nh) {} : scout_(nullptr), nh_(nh) {}
ScoutROSMessenger::ScoutROSMessenger(ScoutBase *scout, ros::NodeHandle *nh) ScoutROSMessenger::ScoutROSMessenger(ScoutBase *scout, ros::NodeHandle *nh)
: scout_(scout), nh_(nh) {} : scout_(scout), nh_(nh) {}
void ScoutROSMessenger::SetupSubscription() { void ScoutROSMessenger::SetupSubscription() {
// odometry publisher // odometry publisher
odom_publisher_ = nh_->advertise<nav_msgs::Odometry>(odom_frame_, 50); odom_publisher_ = nh_->advertise<nav_msgs::Odometry>(odom_topic_name_, 50);
status_publisher_ = status_publisher_ =
nh_->advertise<scout_msgs::ScoutStatus>("/scout_status", 10); nh_->advertise<scout_msgs::ScoutStatus>("/scout_status", 10);
@@ -106,6 +108,7 @@ void ScoutROSMessenger::LightCmdCallback(
} }
} }
void ScoutROSMessenger::PublishStateToROS() { void ScoutROSMessenger::PublishStateToROS() {
current_time_ = ros::Time::now(); current_time_ = ros::Time::now();
double dt = (current_time_ - last_time_).toSec(); double dt = (current_time_ - last_time_).toSec();
@@ -145,7 +148,6 @@ void ScoutROSMessenger::PublishStateToROS() {
status_msg.rear_light_state.mode = state.rear_light_state.mode; status_msg.rear_light_state.mode = state.rear_light_state.mode;
status_msg.rear_light_state.custom_value = status_msg.rear_light_state.custom_value =
state.front_light_state.custom_value; state.front_light_state.custom_value;
status_publisher_.publish(status_msg); status_publisher_.publish(status_msg);
// publish odometry and tf // publish odometry and tf
@@ -166,6 +168,7 @@ void ScoutROSMessenger::PublishSimStateToROS(double linear, double angular) {
init_run = false; init_run = false;
return; return;
} }
// publish scout state message // publish scout state message
scout_msgs::ScoutStatus status_msg; scout_msgs::ScoutStatus status_msg;
@@ -236,7 +239,7 @@ void ScoutROSMessenger::PublishOdometryToROS(double linear, double angular,
// publish odometry and tf messages // publish odometry and tf messages
nav_msgs::Odometry odom_msg; nav_msgs::Odometry odom_msg;
odom_msg.header.stamp = current_time_; odom_msg.header.stamp = current_time_;
odom_msg.header.frame_id = odom_frame_; odom_msg.header.frame_id = "testes";
odom_msg.child_frame_id = base_frame_; odom_msg.child_frame_id = base_frame_;
odom_msg.pose.pose.position.x = position_x_; odom_msg.pose.pose.position.x = position_x_;

View File

@@ -1,4 +0,0 @@
<launch>
<!-- Scout base only (with no onboard sensors) in an empty world -->
<include file="$(find scout_gazebo_sim)/launch/scout_empty_world.launch" />
</launch>

View File

@@ -1,4 +0,0 @@
<launch>
<!-- Scout base with a hokuyo laser in an testing world -->
<include file="$(find scout_gazebo_sim)/launch/scout_playpen.launch" />
</launch>

View File

@@ -1,6 +1,18 @@
<launch> <launch>
<arg name="port_name" value="can0" />
<arg name="simulated_robot" value="false" />
<arg name = "model_xacro" default = "$(find scout_description)/urdf/scout_v2.xacro" />
<arg name ="odom_topic_name" default = "odomsdas"/>
<include file="$(find scout_base)/launch/scout_base.launch" > <include file="$(find scout_base)/launch/scout_base.launch" >
<arg name="port_name" default="can0" /> <arg name="port_name" default="$(arg port_name)" />
<arg name="simulated_robot" default="false" /> <arg name="simulated_robot" default="$(arg simulated_robot)" />
<arg name="odom_topic_name" default="$(arg odom_topic_name)" />
</include>
<include file="$(find scout_description)/launch/description.launch" >
<arg name = "model_xacro" default = "$(arg model_xacro)" />
</include> </include>
</launch> </launch>

View File

@@ -1,6 +1,18 @@
<launch> <launch>
<arg name="port_name" value="/dev/ttyUSB0" />
<arg name="simulated_robot" value="false" />
<arg name = "model_xacro" default = "$(find scout_description)/urdf/scout_v2.xacro" />
<arg name ="odom_topic_name" default = "odomsdas"/>
<include file="$(find scout_base)/launch/scout_base.launch" > <include file="$(find scout_base)/launch/scout_base.launch" >
<arg name="port_name" value="/dev/ttyUSB0" /> <arg name="port_name" default="$(arg port_name)" />
<arg name="simulated_robot" value="false" /> <arg name="simulated_robot" default="$(arg simulated_robot)" />
<arg name="odom_topic_name" default="$(arg odom_topic_name)" />
</include>
<include file="$(find scout_description)/launch/description.launch" >
<arg name = "model_xacro" default = "$(arg model_xacro)" />
</include> </include>
</launch> </launch>

View File

@@ -1,4 +0,0 @@
<launch>
<include file="$(find scout_base)/launch/scout_base_sim.launch" />
<include file="$(find scout_webots_sim)/launch/scout_base.launch" />
</launch>

View File

@@ -0,0 +1,13 @@
cmake_minimum_required(VERSION 2.8.3)
project(scout_description)
find_package(catkin REQUIRED COMPONENTS roslaunch)
catkin_package()
# roslaunch_add_file_check(launch)
install(
DIRECTORY launch meshes urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

View File

@@ -0,0 +1,8 @@
<launch>
<arg name = "model_xacro" default = "$(find scout_description)/urdf/scout_v2.xacro" />
<arg name="model" />
<param name="robot_description" command="$(find xacro)/xacro $(arg model_xacro)"/>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
</launch>

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,15 @@
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor />
<created>2020-03-27T18:56:12.965296</created>
<modified>2020-03-27T18:56:12.965305</modified>
<unit name="meter" meter="1.0" />
<up_axis>Z_UP</up_axis>
</asset>
<library_visual_scenes>
<visual_scene id="myscene" />
</library_visual_scenes>
<scene>
<instance_visual_scene url="#myscene" />
</scene>
</COLLADA>

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,30 @@
<?xml version="1.0"?>
<package>
<name>scout_description</name>
<version>0.4.2</version>
<description>AgileX Scout Husky URDF description</description>
<author email="rgariepy@clearpathrobotics.com">Ryan Gariepy</author>
<author email="pmukherj@clearpathrobotics.com">Prasenjit Mukherjee</author>
<author email="mpurvis@clearpathrobotics.com">Mike Purvis</author>
<author email="paul@bovbel.com">Paul Bovbel</author>
<author email="dash@clearpathrobotics.com">Devon Ash</author>
<maintainer email="paul@bovbel.com">Paul Bovbel</maintainer>
<maintainer email="tbaltovski@clearpathrobotics.com">Tony Baltovski</maintainer>
<url type="website">http://ros.org/wiki/scout_description</url>
<url type="bugtracker">https://github.com/husky/husky/issues</url>
<url type="repository">https://github.com/husky/husky</url>
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roslaunch</build_depend>
<run_depend>urdf</run_depend>
<run_depend>xacro</run_depend>
<run_depend>lms1xx</run_depend>
<export>
</export>
</package>

View File

@@ -0,0 +1,137 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from scout_description/urdf/scout_v2_webots.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="scout_v2">
<!-- Base link -->
<link name="base_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://scout_description/meshes/base_link.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.008"/>
<geometry>
<box size="0.925 0.38 0.21"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.035"/>
<geometry>
<box size="0.154166666667 0.627 0.07"/>
</geometry>
</collision>
<inertial>
<mass value="40"/>
<origin xyz="0.0 0.0 0.0"/>
<inertia ixx="2.288641" ixy="0" ixz="0" iyy="5.103976" iyz="0" izz="3.431465"/>
</inertial>
</link>
<link name="front_right_wheel_link">
<inertial>
<mass value="3"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://scout_description/meshes/wheel_type1.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.11653" radius="0.16459"/>
</geometry>
</collision>
</link>
<joint name="front_right_wheel" type="continuous">
<parent link="base_link"/>
<child link="front_right_wheel_link"/>
<origin rpy="3.14 0 0" xyz="0.249 -0.29153 -0.0702"/>
<axis rpy="0 0 0" xyz="0 -1 0"/>
</joint>
<link name="front_left_wheel_link">
<inertial>
<mass value="3"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://scout_description/meshes/wheel_type2.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.11653" radius="0.16459"/>
</geometry>
</collision>
</link>
<joint name="front_left_wheel" type="continuous">
<parent link="base_link"/>
<child link="front_left_wheel_link"/>
<origin rpy="0 0 0" xyz="0.249 0.29153 -0.0702"/>
<axis rpy="0 0 0" xyz="0 -1 0"/>
</joint>
<link name="rear_left_wheel_link">
<inertial>
<mass value="3"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://scout_description/meshes/wheel_type1.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.11653" radius="0.16459"/>
</geometry>
</collision>
</link>
<joint name="rear_left_wheel" type="continuous">
<parent link="base_link"/>
<child link="rear_left_wheel_link"/>
<origin rpy="0 0 0" xyz="-0.249 0.29153 -0.0702"/>
<axis rpy="0 0 0" xyz="0 -1 0"/>
</joint>
<link name="rear_right_wheel_link">
<inertial>
<mass value="3"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://scout_description/meshes/wheel_type2.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.11653" radius="0.16459"/>
</geometry>
</collision>
</link>
<joint name="rear_right_wheel" type="continuous">
<parent link="base_link"/>
<child link="rear_right_wheel_link"/>
<origin rpy="3.14 0 0" xyz="-0.249 -0.29153 -0.0702"/>
<axis rpy="0 0 0" xyz="0 -1 0"/>
</joint>
<!-- Additional definitions -->
<!-- <xacro:include filename="$(arg urdf_extras)" /> -->
<!-- Gazebo definitions -->
<!-- <xacro:include filename="$(find scout_description)/urdf/scout_v2.gazebo" /> -->
</robot>

View File

@@ -0,0 +1,86 @@
<?xml version="1.0"?>
<robot name="scout_v2"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="robot_namespace" default="/" />
<xacro:include filename="$(find scout_description)/urdf/scout_wheel_type1.xacro" />
<xacro:include filename="$(find scout_description)/urdf/scout_wheel_type2.xacro" />
<!-- Variables -->
<xacro:property name="M_PI" value="3.14159"/>
<!-- Vehicle Geometries -->
<xacro:property name="base_x_size" value="0.9250000" />
<xacro:property name="base_y_size" value="0.380000" />
<xacro:property name="base_z_size" value="0.210000" />
<xacro:property name="wheelbase" value="0.498" />
<xacro:property name="track" value="0.58306" />
<xacro:property name="wheel_vertical_offset" value="-0.0702" />
<xacro:property name="wheel_length" value="1.1653e-01" />
<xacro:property name="wheel_radius" value="1.6459e-01" />
<!-- Base link -->
<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://scout_description/meshes/base_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.008" rpy="0 0 0" />
<geometry>
<box size="${base_x_size} ${base_y_size} ${base_z_size}"/>
</geometry>
</collision>
<collision>
<origin xyz="0 0 ${base_z_size/6}" rpy="0 0 0" />
<geometry>
<box size="${base_x_size/6} ${base_y_size*1.65} ${base_z_size/3}"/>
</geometry>
</collision>
</link>
<link name="base_footprint"/>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${wheel_vertical_offset - wheel_radius}" rpy="0 0 0" />
<parent link="base_link" />
<child link="base_footprint" />
</joint>
<link name="inertial_link">
<inertial>
<mass value="40" />
<origin xyz="0.0 0.0 0.0" />
<inertia ixx="2.288641" ixy="0" ixz="0" iyy="5.103976" iyz="0" izz="3.431465" />
</inertial>
</link>
<joint name="inertial_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_link" />
<child link="inertial_link" />
</joint>
<!-- Scout wheel macros -->
<!-- wheel labeled from 0 to 3, conter-clockwise, starting from front right wheel -->
<!-- motor 1 and 2 (left side) are mechanically installed in a reversed direction -->
<xacro:scout_wheel_type1 wheel_prefix="front_right">
<origin xyz="${wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
</xacro:scout_wheel_type1>
<xacro:scout_wheel_type2 wheel_prefix="front_left">
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:scout_wheel_type2>
<xacro:scout_wheel_type1 wheel_prefix="rear_left">
<origin xyz="${-wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:scout_wheel_type1>
<xacro:scout_wheel_type2 wheel_prefix="rear_right">
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
</xacro:scout_wheel_type2>
</robot>

View File

@@ -0,0 +1,59 @@
<?xml version="1.0"?>
<!--
Software License Agreement (BSD)
\file scout_wheel.xacro (adapted from wheel.urdf.xacro in husky_description)
\authors Paul Bovbel <pbovbel@clearpathrobotics.com>
Ruixiang Du <ruixiang.du@westonrobot.com>
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved.
\copyright Copyright (c) 2020, Weston Robot Pte. Ltd., All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the
following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
following disclaimer in the documentation and/or other materials provided with the distribution.
* Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="scout_wheel">
<xacro:macro name="scout_wheel_type1" params="wheel_prefix *joint_pose">
<link name="${wheel_prefix}_wheel_link">
<inertial>
<mass value="3" />
<origin xyz="0 0 0" />
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://scout_description/meshes/wheel_type1.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder length="${wheel_length}" radius="${wheel_radius}" />
</geometry>
</collision>
</link>
<joint name="${wheel_prefix}_wheel" type="continuous">
<parent link="base_link"/>
<child link="${wheel_prefix}_wheel_link"/>
<xacro:insert_block name="joint_pose"/>
<axis xyz="0 -1 0" rpy="0 0 0" />
</joint>
</xacro:macro>
</robot>

View File

@@ -0,0 +1,59 @@
<?xml version="1.0"?>
<!--
Software License Agreement (BSD)
\file scout_wheel.xacro (adapted from wheel.urdf.xacro in husky_description)
\authors Paul Bovbel <pbovbel@clearpathrobotics.com>
Ruixiang Du <ruixiang.du@westonrobot.com>
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved.
\copyright Copyright (c) 2020, Weston Robot Pte. Ltd., All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the
following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
following disclaimer in the documentation and/or other materials provided with the distribution.
* Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="scout_wheel">
<xacro:macro name="scout_wheel_type2" params="wheel_prefix *joint_pose">
<link name="${wheel_prefix}_wheel_link">
<inertial>
<mass value="3" />
<origin xyz="0 0 0" />
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://scout_description/meshes/wheel_type2.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder length="${wheel_length}" radius="${wheel_radius}" />
</geometry>
</collision>
</link>
<joint name="${wheel_prefix}_wheel" type="continuous">
<parent link="base_link"/>
<child link="${wheel_prefix}_wheel_link"/>
<xacro:insert_block name="joint_pose"/>
<axis xyz="0 -1 0" rpy="0 0 0" />
</joint>
</xacro:macro>
</robot>

202
scout_viz/CMakeLists.txt Normal file
View File

@@ -0,0 +1,202 @@
cmake_minimum_required(VERSION 3.0.2)
project(scout_viz)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs # Or other packages containing msgs
# )
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES scout_viz
# CATKIN_DEPENDS other_catkin_pkg
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
# ${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/scout_viz.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/scout_viz_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_scout_viz.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

View File

@@ -0,0 +1,10 @@
<launch>
<arg name = "model_xacro" default = "$(find scout_description)/urdf/scout_v2.xacro" />
<arg name="model" />
<include file="$(find scout_description)/launch/description.launch" >
<arg name = "model_xacro" default = "$(arg model_xacro)" />
</include>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find scout_viz)/rviz/model_display.rviz" />
</launch>

59
scout_viz/package.xml Normal file
View File

@@ -0,0 +1,59 @@
<?xml version="1.0"?>
<package format="2">
<name>scout_viz</name>
<version>0.0.0</version>
<description>The scout_viz package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="tanpinda@todo.todo">tanpinda</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/scout_viz</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>

View File

@@ -0,0 +1,209 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /RobotModel1
Splitter Ratio: 0.5
Tree Height: 732
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
chassis_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_left_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_right_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
inertial_link:
Alpha: 1
Show Axes: false
Show Trail: false
rear_left_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rear_right_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: true
base_link:
Value: true
chassis_link:
Value: true
front_left_wheel_link:
Value: true
front_right_wheel_link:
Value: true
inertial_link:
Value: true
rear_left_wheel_link:
Value: true
rear_right_wheel_link:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
base_link:
chassis_link:
front_left_wheel_link:
{}
front_right_wheel_link:
{}
rear_left_wheel_link:
{}
rear_right_wheel_link:
{}
inertial_link:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: base_link
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 2.9432930946350098
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0.027046792209148407
Y: -0.03490818291902542
Z: -0.09952529519796371
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.5447957515716553
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 4.27542781829834
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1029
Hide Left Dock: false
Hide Right Dock: true
QMainWindow State: 000000ff00000000fd00000004000000000000015600000367fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000367000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000074d0000003efc0100000002fb0000000800540069006d006501000000000000074d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005f10000036700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: true
Width: 1869
X: 632
Y: 291

View File

@@ -0,0 +1,209 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /RobotModel1
Splitter Ratio: 0.5
Tree Height: 732
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
chassis_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_left_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_right_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
inertial_link:
Alpha: 1
Show Axes: false
Show Trail: false
rear_left_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rear_right_wheel_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: true
base_link:
Value: true
chassis_link:
Value: true
front_left_wheel_link:
Value: true
front_right_wheel_link:
Value: true
inertial_link:
Value: true
rear_left_wheel_link:
Value: true
rear_right_wheel_link:
Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
base_link:
chassis_link:
front_left_wheel_link:
{}
front_right_wheel_link:
{}
rear_left_wheel_link:
{}
rear_right_wheel_link:
{}
inertial_link:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: odom
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 2.9432930946350098
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0.027046792209148407
Y: -0.03490818291902542
Z: -0.09952529519796371
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.5447957515716553
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 4.27542781829834
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1029
Hide Left Dock: false
Hide Right Dock: true
QMainWindow State: 000000ff00000000fd00000004000000000000015600000367fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000367000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000074d0000003efc0100000002fb0000000800540069006d006501000000000000074d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005f10000036700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: true
Width: 1869
X: 632
Y: 291