diff --git a/.gitignore b/.gitignore
new file mode 100644
index 0000000..0704271
--- /dev/null
+++ b/.gitignore
@@ -0,0 +1,57 @@
+devel/
+logs/
+build/
+bin/
+lib/
+msg_gen/
+srv_gen/
+msg/*Action.msg
+msg/*ActionFeedback.msg
+msg/*ActionGoal.msg
+msg/*ActionResult.msg
+msg/*Feedback.msg
+msg/*Goal.msg
+msg/*Result.msg
+msg/_*.py
+build_isolated/
+devel_isolated/
+
+# Webots temporary files
+scout_webots_sim/worlds/.scout_base.wbproj
+
+# Generated by dynamic reconfigure
+*.cfgc
+/cfg/cpp/
+/cfg/*.py
+
+# Ignore generated docs
+*.dox
+*.wikidoc
+
+# eclipse stuff
+.project
+.cproject
+
+# Visual studio code stuff
+*.vscode
+
+# qcreator stuff
+CMakeLists.txt.user
+
+srv/_*.py
+*.pcd
+*.pyc
+qtcreator-*
+*.user
+
+/planning/cfg
+/planning/docs
+/planning/src
+
+*~
+
+# Emacs
+.#*
+
+# Catkin custom files
+CATKIN_IGNORE
diff --git a/scout_base/CMakeLists.txt b/scout_base/CMakeLists.txt
index 8e858e2..413e441 100644
--- a/scout_base/CMakeLists.txt
+++ b/scout_base/CMakeLists.txt
@@ -51,6 +51,10 @@ set_property(TARGET scout_messenger PROPERTY POSITION_INDEPENDENT_CODE ON)
add_executable(scout_base_node src/scout_base_node.cpp)
target_link_libraries(scout_base_node scout_messenger ${catkin_LIBRARIES})
+add_executable(scout_base_sim_node src/scout_base_sim_node.cpp)
+target_link_libraries(scout_base_sim_node scout_messenger ${catkin_LIBRARIES})
+
+
#############
## Install ##
#############
diff --git a/scout_base/launch/scout_base_sim.launch b/scout_base/launch/scout_base_sim.launch
new file mode 100644
index 0000000..a45e6dd
--- /dev/null
+++ b/scout_base/launch/scout_base_sim.launch
@@ -0,0 +1,22 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/scout_base/src/scout_base_node.cpp b/scout_base/src/scout_base_node.cpp
index a3b7e05..633612a 100644
--- a/scout_base/src/scout_base_node.cpp
+++ b/scout_base/src/scout_base_node.cpp
@@ -40,13 +40,13 @@ int main(int argc, char **argv)
}
messenger.SetupSubscription();
- // publish robot state at 20Hz while listening to twist commands
- ros::Rate rate_20hz(20); // 20Hz
+ // publish robot state at 50Hz while listening to twist commands
+ ros::Rate rate_50hz(50); // 50Hz
while (true)
{
messenger.PublishStateToROS();
ros::spinOnce();
- rate_20hz.sleep();
+ rate_50hz.sleep();
}
return 0;
diff --git a/scout_base/src/scout_base_sim_node.cpp b/scout_base/src/scout_base_sim_node.cpp
new file mode 100644
index 0000000..f7b9d77
--- /dev/null
+++ b/scout_base/src/scout_base_sim_node.cpp
@@ -0,0 +1,47 @@
+#include
+
+#include
+#include
+#include
+#include
+
+#include "scout_sdk/scout_base.hpp"
+#include "scout_base/scout_messenger.hpp"
+
+using namespace wescore;
+
+int main(int argc, char **argv)
+{
+ // setup ROS node
+ ros::init(argc, argv, "scout_odom");
+ ros::NodeHandle node(""), private_node("~");
+
+ // instantiate a robot object
+ ScoutBase robot;
+ ScoutROSMessenger messenger(&robot, &node);
+
+ // fetch parameters before connecting to robot
+ std::string port_name;
+ private_node.param("port_name", port_name, std::string("can0"));
+ private_node.param("odom_frame", messenger.odom_frame_, std::string("odom"));
+ private_node.param("base_frame", messenger.base_frame_, std::string("base_link"));
+ private_node.param("simulated_robot", messenger.simulated_robot_, true);
+ private_node.param("control_rate", messenger.sim_control_rate_, 50);
+
+ // no connection for simulated robot
+ // setup ROS subscription
+ messenger.SetupSubscription();
+
+ // publish robot state at 50Hz while listening to twist commands
+ double linear, angular;
+ ros::Rate rate_50hz(50); // 50Hz
+ while (true)
+ {
+ messenger.GetCurrentMotionCmdForSim(linear, angular);
+ messenger.PublishSimStateToROS(linear, angular);
+ ros::spinOnce();
+ rate_50hz.sleep();
+ }
+
+ return 0;
+}
\ No newline at end of file
diff --git a/scout_bringup/launch/scout_base_gazebo_sim.launch b/scout_bringup/launch/scout_base_gazebo_sim.launch
new file mode 100644
index 0000000..9525b24
--- /dev/null
+++ b/scout_bringup/launch/scout_base_gazebo_sim.launch
@@ -0,0 +1,4 @@
+
+
+
+
diff --git a/scout_bringup/launch/scout_base_sim.launch b/scout_bringup/launch/scout_base_webots_sim.launch
similarity index 100%
rename from scout_bringup/launch/scout_base_sim.launch
rename to scout_bringup/launch/scout_base_webots_sim.launch
diff --git a/scout_description/rviz/model_display.rviz b/scout_description/rviz/model_display.rviz
index ed89270..337a0b1 100644
--- a/scout_description/rviz/model_display.rviz
+++ b/scout_description/rviz/model_display.rviz
@@ -63,11 +63,11 @@ Visualization Manager:
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
- base_footprint:
+ base_link:
Alpha: 1
Show Axes: false
Show Trail: false
- base_link:
+ chassis_link:
Alpha: 1
Show Axes: false
Show Trail: false
@@ -96,10 +96,6 @@ Visualization Manager:
Show Axes: false
Show Trail: false
Value: true
- world:
- Alpha: 1
- Show Axes: false
- Show Trail: false
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
@@ -111,10 +107,10 @@ Visualization Manager:
Frame Timeout: 15
Frames:
All Enabled: true
- base_footprint:
- Value: true
base_link:
Value: true
+ chassis_link:
+ Value: true
front_left_wheel_link:
Value: true
front_right_wheel_link:
@@ -125,35 +121,31 @@ Visualization Manager:
Value: true
rear_right_wheel_link:
Value: true
- world:
- Value: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
- world:
- base_link:
- base_footprint:
- {}
+ base_link:
+ chassis_link:
front_left_wheel_link:
{}
front_right_wheel_link:
{}
- inertial_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: world
+ Fixed Frame: base_link
Frame Rate: 30
Name: root
Tools:
@@ -214,4 +206,4 @@ Window Geometry:
collapsed: true
Width: 1869
X: 632
- Y: 381
+ Y: 291
diff --git a/scout_description/rviz/navigation.rviz b/scout_description/rviz/navigation.rviz
new file mode 100644
index 0000000..00f509a
--- /dev/null
+++ b/scout_description/rviz/navigation.rviz
@@ -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:
+ 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:
+ 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
diff --git a/scout_description/urdf/scout_v2.gazebo b/scout_description/urdf/scout_v2.gazebo
index 0cdc2b1..765a304 100644
--- a/scout_description/urdf/scout_v2.gazebo
+++ b/scout_description/urdf/scout_v2.gazebo
@@ -1,10 +1,12 @@
+
diff --git a/scout_description/urdf/scout_v2.urdf b/scout_description/urdf/scout_v2.urdf
deleted file mode 100644
index 6031ca5..0000000
--- a/scout_description/urdf/scout_v2.urdf
+++ /dev/null
@@ -1,277 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- transmission_interface/SimpleTransmission
-
- 1
-
-
- hardware_interface/VelocityJointInterface
-
-
-
-
-
-
-
-
-
-
-
-
-
- transmission_interface/SimpleTransmission
-
- 1
-
-
- hardware_interface/VelocityJointInterface
-
-
-
-
-
-
-
-
-
-
-
-
-
- transmission_interface/SimpleTransmission
-
- 1
-
-
- hardware_interface/VelocityJointInterface
-
-
-
-
-
-
-
-
-
-
-
-
-
- transmission_interface/SimpleTransmission
-
- 1
-
-
- hardware_interface/VelocityJointInterface
-
-
-
-
-
- /
-
-
-
-
-
diff --git a/scout_description/urdf/scout_v2.xacro b/scout_description/urdf/scout_v2.xacro
index 0b68053..20338a0 100644
--- a/scout_description/urdf/scout_v2.xacro
+++ b/scout_description/urdf/scout_v2.xacro
@@ -24,22 +24,6 @@
-
-
-
-
-
-
-
-
-
-
-
@@ -48,14 +32,6 @@
-
-
-
-
-
-
-
@@ -70,15 +46,37 @@
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/scout_gazebo_sim/launch/scout_empty_world.launch b/scout_gazebo_sim/launch/scout_empty_world.launch
index 64be720..aa77d72 100644
--- a/scout_gazebo_sim/launch/scout_empty_world.launch
+++ b/scout_gazebo_sim/launch/scout_empty_world.launch
@@ -14,5 +14,5 @@
-
+
diff --git a/scout_gazebo_sim/launch/spawn_scout_v2.launch b/scout_gazebo_sim/launch/spawn_scout_v2.launch
index 3595e78..c7b962e 100644
--- a/scout_gazebo_sim/launch/spawn_scout_v2.launch
+++ b/scout_gazebo_sim/launch/spawn_scout_v2.launch
@@ -9,7 +9,7 @@
-
+
diff --git a/scout_gazebo_sim/src/scout_skid_steer_controller.cpp b/scout_gazebo_sim/src/scout_skid_steer_controller.cpp
index 1a704b1..ccaa453 100644
--- a/scout_gazebo_sim/src/scout_skid_steer_controller.cpp
+++ b/scout_gazebo_sim/src/scout_skid_steer_controller.cpp
@@ -26,39 +26,5 @@ int main(int argc, char **argv) {
ros::spin();
- // // instantiate a robot object
- // ScoutBase robot;
- // ScoutROSMessenger messenger(&robot, &node);
-
- // // fetch parameters before connecting to robot
- // std::string port_name;
- // private_node.param("port_name", port_name,
- // std::string("can0")); private_node.param("odom_frame",
- // messenger.odom_frame_, std::string("odom"));
- // private_node.param("base_frame", messenger.base_frame_,
- // std::string("base_link")); private_node.param("simulated_robot",
- // messenger.simulated_robot_, false);
-
- // // connect to robot and setup ROS subscription
- // if (port_name.find("can") != std::string::npos)
- // {
- // robot.Connect(port_name);
- // ROS_INFO("Using CAN bus to talk with the robot");
- // }
- // else
- // {
- // robot.Connect(port_name, 115200);
- // ROS_INFO("Using UART to talk with the robot");
- // }
- // messenger.SetupSubscription();
-
- // publish robot state at 20Hz while listening to twist commands
- // ros::Rate rate_20hz(20); // 20Hz
- // while (true) {
- // messenger.PublishStateToROS();
- // ros::spinOnce();
- // rate_20hz.sleep();
- // }
-
return 0;
}
\ No newline at end of file