saved work

This commit is contained in:
Ruixiang Du
2020-03-26 19:06:34 +08:00
parent 38510eb257
commit dbf04d03d8
10 changed files with 151 additions and 57 deletions

3
NOTE.md Normal file
View File

@@ -0,0 +1,3 @@
```
$ rostopic pub -1 /scout_motor_fl_controller/command std_msgs/Float64 "data: 0.5"
```

View File

@@ -1,5 +1,10 @@
<?xml version="1.0"?>
<launch>
<param name="robot_description" command="$(find xacro)/xacro '$(find scout_description)/urdf/scout_v2.xacro'" />
<arg name="robot_namespace" default="/"/>
<arg name="urdf_extras" default="$(find scout_description)/urdf/empty.urdf"/>
<param name="robot_description" command="$(find xacro)/xacro '$(find scout_description)/urdf/scout_v2.xacro'
--inorder
robot_namespace:=$(arg robot_namespace)
urdf_extras:=$(arg urdf_extras)" />
</launch>

View File

@@ -16,7 +16,7 @@
<!-- Controller configurations -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace></robotNamespace>
<robotNamespace>$(arg robot_namespace)</robotNamespace>
</plugin>
</gazebo>

View File

@@ -3,6 +3,7 @@
<robot name="scout_v2"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="robot_namespace" default="/" />
<xacro:arg name="urdf_extras" default="empty.urdf" />
<xacro:include filename="$(find scout_description)/urdf/scout_wheel_type1.xacro" />

View File

@@ -7,11 +7,9 @@ find_package(catkin REQUIRED COMPONENTS
roslaunch
roslint
roscpp
sensor_msgs
std_msgs
sensor_msgs
geometry_msgs
scout_msgs
scout_sdk
tf2
tf2_ros
)

View File

@@ -10,17 +10,39 @@
#ifndef SCOUT_SKID_STEER_HPP
#define SCOUT_SKID_STEER_HPP
#include <string>
#include <geometry_msgs/Twist.h>
#include <ros/ros.h>
#include <string>
namespace wescore {
class ScoutSkidSteer {
public:
ScoutSkidSteer(std::string robot_name);
ScoutSkidSteer(ros::NodeHandle *nh, std::string robot_name = "");
void SetupSubscription();
private:
std::string robot_name;
std::string robot_name_;
std::string motor_fr_topic_;
std::string motor_fl_topic_;
std::string motor_rl_topic_;
std::string motor_rr_topic_;
std::string cmd_topic_;
const double SCOUT_WHEELBASE = 0.498;
const double SCOUT_WHEEL_RADIUS = 0.16459;
ros::NodeHandle *nh_;
ros::Publisher motor_fr_pub_;
ros::Publisher motor_fl_pub_;
ros::Publisher motor_rl_pub_;
ros::Publisher motor_rr_pub_;
ros::Subscriber cmd_sub_;
void TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg);
};
} // namespace wescore

View File

@@ -25,6 +25,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
-->
<launch>
<arg name="robot_namespace" default="/"/>
<arg name="world_name" default="worlds/empty.world"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
@@ -37,7 +38,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
<arg name="debug" value="false"/>
</include>
<include file="$(find scout_gazebo)/launch/spawn_scout_v2.launch"></include>
<include file="$(find scout_gazebo_sim)/launch/spawn_scout_v2.launch"></include>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find scout_description)/rviz/model_display.rviz" />
</launch>

View File

@@ -5,6 +5,8 @@
<arg name="z" default="0.0"/>
<arg name="yaw" default="0.0"/>
<arg name="robot_namespace" default="/"/>
<!-- these are the arguments you can pass this launch file, for example paused:=true -->
<arg name="paused" default="true" />
<arg name="use_sim_time" default="false" />
@@ -12,7 +14,9 @@
<arg name="headless" default="false" />
<arg name="debug" default="true" />
<include file="$(find scout_description)/launch/scout_v2_stock.launch"></include>
<include file="$(find scout_description)/launch/scout_v2_stock.launch">
<arg name="robot_namespace" value="$(arg robot_namespace)" />
</include>
<node name="spawn_scout_model" pkg="gazebo_ros" type="spawn_model" args="-x $(arg x)
-y $(arg y)
@@ -21,14 +25,16 @@
-unpause
-urdf
-param robot_description
-model 'scout_v2'" />
-model 'scout$(arg robot_namespace)'" />
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find scout_gazebo)/config/scout_v2_control.yaml" command="load"/>
<rosparam file="$(find scout_gazebo_sim)/config/scout_v2_control.yaml" command="load"/>
<!-- load the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/" args="scout_state_controller scout_motor_fr_controller scout_motor_fl_controller scout_motor_rl_controller scout_motor_rr_controller"/>
<!-- <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" /> -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="scout_state_controller scout_motor_fr_controller scout_motor_fl_controller scout_motor_rl_controller scout_motor_rr_controller"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="scout_skid_steer_controller" pkg="scout_gazebo_sim" type="scout_skid_steer_controller">
<param name="robot_namespace" type="string" value="$(arg robot_namespace)" />
</node>
</launch>

View File

@@ -9,6 +9,52 @@
#include "scout_gazebo/scout_skid_steer.hpp"
#include <geometry_msgs/Twist.h>
#include <std_msgs/Float64.h>
namespace wescore {
}
ScoutSkidSteer::ScoutSkidSteer(ros::NodeHandle *nh, std::string robot_name)
: nh_(nh), robot_name_(robot_name) {
motor_fr_topic_ = robot_name_ + "/scout_motor_fr_controller/command";
motor_fl_topic_ = robot_name_ + "/scout_motor_fl_controller/command";
motor_rl_topic_ = robot_name_ + "/scout_motor_rl_controller/command";
motor_rr_topic_ = robot_name_ + "/scout_motor_rr_controller/command";
cmd_topic_ = robot_name_ + "/cmd_vel";
}
void ScoutSkidSteer::SetupSubscription() {
// command subscriber
cmd_sub_ = nh_->subscribe<geometry_msgs::Twist>(
cmd_topic_, 5, &ScoutSkidSteer::TwistCmdCallback, this);
// motor command publisher
motor_fr_pub_ = nh_->advertise<std_msgs::Float64>(motor_fr_topic_, 50);
motor_fl_pub_ = nh_->advertise<std_msgs::Float64>(motor_fl_topic_, 50);
motor_rl_pub_ = nh_->advertise<std_msgs::Float64>(motor_rl_topic_, 50);
motor_rr_pub_ = nh_->advertise<std_msgs::Float64>(motor_rr_topic_, 50);
}
void ScoutSkidSteer::TwistCmdCallback(
const geometry_msgs::Twist::ConstPtr &msg) {
std_msgs::Float64 motor_cmd[4];
double driving_vel = msg->linear.x;
double steering_vel = msg->angular.z;
double left_side_velocity =
(driving_vel - steering_vel * SCOUT_WHEELBASE) / SCOUT_WHEEL_RADIUS;
double right_side_velocity =
(driving_vel + steering_vel * SCOUT_WHEELBASE) / SCOUT_WHEEL_RADIUS;
motor_cmd[0].data = right_side_velocity;
motor_cmd[1].data = -left_side_velocity;
motor_cmd[2].data = -left_side_velocity;
motor_cmd[3].data = right_side_velocity;
motor_fr_pub_.publish(motor_cmd[0]);
motor_fl_pub_.publish(motor_cmd[1]);
motor_rl_pub_.publish(motor_cmd[2]);
motor_rr_pub_.publish(motor_cmd[3]);
}
} // namespace wescore

View File

@@ -1,52 +1,64 @@
#include <string>
#include <nav_msgs/Odometry.h>
#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
#include <string>
#include "scout_gazebo/scout_skid_steer.hpp"
using namespace wescore;
int main(int argc, char **argv)
{
// setup ROS node
ros::init(argc, argv, "scout_odom");
ros::NodeHandle node(""), private_node("~");
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
std::string robot_namespace;
private_node.param<std::string>("robot_namespace", robot_namespace,
std::string("scout_default"));
// // 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_, false);
ROS_INFO("Namespace: %s", robot_namespace.c_str());
// // 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();
ScoutSkidSteer skid_steer_controller(&node, robot_namespace);
skid_steer_controller.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();
// }
ros::spin();
return 0;
// // 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_, 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;
}