updated launch files and readme

This commit is contained in:
Ruixiang Du
2019-10-10 11:13:11 +08:00
parent fff2e3f73b
commit ef72005125
11 changed files with 130 additions and 54 deletions

View File

@@ -1,17 +0,0 @@
<launch>
<!--
<node name="scout_odom" pkg="scout_base" type="scout_base_node" output="screen">
<param name="port_name" type="string" value="can0" />
<param name="odom_frame" type="string" value="odom" />
<param name="base_frame" type="string" value="base_link" />
<param name="simulated_robot" type="bool" value="false" />
</node>
-->
<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

@@ -1,10 +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="port_name" default="can0" />
<arg name="simulated_robot" default="false" />
<node name="scout_base_node" pkg="scout_base" type="scout_base_node" output="screen">
<param name="port_name" type="string" value="can0" />
<param name="port_name" type="string" value="$(arg port_name)" />
<param name="simulated_robot" type="bool" value="$(arg simulated_robot)" />
<param name="odom_frame" type="string" value="odom" />
<param name="base_frame" type="string" value="base_link" />
<param name="simulated_robot" type="bool" value="false" />
</node>
</launch>

View File

@@ -0,0 +1,6 @@
<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

@@ -16,18 +16,28 @@ int main(int argc, char **argv)
ros::init(argc, argv, "scout_odom");
ros::NodeHandle node(""), private_node("~");
// instantiate a robot
// instantiate a robot object
ScoutBase robot;
ScoutROSMessenger messenger(&robot, &node);
std::string scout_can_port;
private_node.param<std::string>("port_name", scout_can_port, std::string("can0"));
// 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 scout and setup ROS subscription
robot.Connect(scout_can_port);
// 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