fixed state publish rate error (from 20hz to 50hz), gazebo scout v2 sim ready

This commit is contained in:
Ruixiang Du
2020-04-02 11:43:29 +08:00
parent a1efd5b609
commit f73a2e2f59
15 changed files with 392 additions and 368 deletions

View File

@@ -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 ##
#############

View File

@@ -0,0 +1,22 @@
<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_sim_node" pkg="scout_base" type="scout_base_sim_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

@@ -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;

View File

@@ -0,0 +1,47 @@
#include <string>
#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
#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<std::string>("port_name", port_name, std::string("can0"));
private_node.param<std::string>("odom_frame", messenger.odom_frame_, std::string("odom"));
private_node.param<std::string>("base_frame", messenger.base_frame_, std::string("base_link"));
private_node.param<bool>("simulated_robot", messenger.simulated_robot_, true);
private_node.param<int>("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;
}