mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 03:15:01 +08:00
Merge branch 'PD_dev' into 'master'
Pd dev See merge request westonrobot/ros/scout_base!3
This commit is contained in:
@@ -30,6 +30,7 @@ public:
|
||||
|
||||
std::string odom_frame_;
|
||||
std::string base_frame_;
|
||||
std::string odom_topic_name_;
|
||||
|
||||
bool simulated_robot_ = false;
|
||||
int sim_control_rate_ = 50;
|
||||
|
||||
@@ -12,11 +12,15 @@
|
||||
<arg name="port_name" default="can0" />
|
||||
<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">
|
||||
<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 = "odom_topic_name" type="string" value="$(arg odom_topic_name)" />
|
||||
</node>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -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>
|
||||
@@ -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>
|
||||
@@ -27,6 +27,8 @@ int main(int argc, char **argv) {
|
||||
private_node.param<bool>("simulated_robot", messenger.simulated_robot_,
|
||||
false);
|
||||
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_) {
|
||||
// connect to robot and setup ROS subscription
|
||||
|
||||
@@ -13,16 +13,18 @@
|
||||
|
||||
#include "scout_msgs/ScoutStatus.h"
|
||||
|
||||
|
||||
namespace westonrobot {
|
||||
ScoutROSMessenger::ScoutROSMessenger(ros::NodeHandle *nh)
|
||||
: scout_(nullptr), nh_(nh) {}
|
||||
|
||||
|
||||
ScoutROSMessenger::ScoutROSMessenger(ScoutBase *scout, ros::NodeHandle *nh)
|
||||
: scout_(scout), nh_(nh) {}
|
||||
|
||||
void ScoutROSMessenger::SetupSubscription() {
|
||||
// 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_ =
|
||||
nh_->advertise<scout_msgs::ScoutStatus>("/scout_status", 10);
|
||||
|
||||
@@ -106,6 +108,7 @@ void ScoutROSMessenger::LightCmdCallback(
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void ScoutROSMessenger::PublishStateToROS() {
|
||||
current_time_ = ros::Time::now();
|
||||
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.custom_value =
|
||||
state.front_light_state.custom_value;
|
||||
|
||||
status_publisher_.publish(status_msg);
|
||||
|
||||
// publish odometry and tf
|
||||
@@ -166,6 +168,7 @@ void ScoutROSMessenger::PublishSimStateToROS(double linear, double angular) {
|
||||
init_run = false;
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
// publish scout state message
|
||||
scout_msgs::ScoutStatus status_msg;
|
||||
@@ -236,7 +239,7 @@ void ScoutROSMessenger::PublishOdometryToROS(double linear, double angular,
|
||||
// publish odometry and tf messages
|
||||
nav_msgs::Odometry odom_msg;
|
||||
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.pose.pose.position.x = position_x_;
|
||||
|
||||
Reference in New Issue
Block a user