mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
added option to select odom navmsgs topic name
This commit is contained in:
@@ -30,6 +30,7 @@ public:
|
|||||||
|
|
||||||
std::string odom_frame_;
|
std::string odom_frame_;
|
||||||
std::string base_frame_;
|
std::string base_frame_;
|
||||||
|
std::string odom_topic_name_;
|
||||||
|
|
||||||
bool simulated_robot_ = false;
|
bool simulated_robot_ = false;
|
||||||
int sim_control_rate_ = 50;
|
int sim_control_rate_ = 50;
|
||||||
|
|||||||
@@ -11,7 +11,8 @@
|
|||||||
-->
|
-->
|
||||||
<arg name="port_name" default="can0" />
|
<arg name="port_name" default="can0" />
|
||||||
<arg name="simulated_robot" default="false" />
|
<arg name="simulated_robot" default="false" />
|
||||||
<arg name = "model_xacro" default = "$(find scout_base)/description/scout_v2.xacro" />>
|
<arg name = "model_xacro" default = "$(find scout_base)/description/scout_v2.xacro" />
|
||||||
|
<arg name ="odom_topic_name" default = "odom"/>
|
||||||
|
|
||||||
<node name="scout_base_node" pkg="scout_base" type="scout_base_node" output="screen">
|
<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="port_name" type="string" value="$(arg port_name)" />
|
||||||
@@ -19,6 +20,7 @@
|
|||||||
|
|
||||||
<param name="odom_frame" type="string" value="odom" />
|
<param name="odom_frame" type="string" value="odom" />
|
||||||
<param name="base_frame" type="string" value="base_link" />
|
<param name="base_frame" type="string" value="base_link" />
|
||||||
|
<param name = "odom_topic_name" type="string" value="$(arg odom_topic_name)" />
|
||||||
</node>
|
</node>
|
||||||
<param name="robot_description" command="$(find xacro)/xacro $(arg model_xacro)"/>
|
<param name="robot_description" command="$(find xacro)/xacro $(arg model_xacro)"/>
|
||||||
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>
|
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>
|
||||||
|
|||||||
@@ -27,6 +27,8 @@ int main(int argc, char **argv) {
|
|||||||
private_node.param<bool>("simulated_robot", messenger.simulated_robot_,
|
private_node.param<bool>("simulated_robot", messenger.simulated_robot_,
|
||||||
false);
|
false);
|
||||||
private_node.param<int>("control_rate", messenger.sim_control_rate_, 50);
|
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_) {
|
if (!messenger.simulated_robot_) {
|
||||||
// connect to robot and setup ROS subscription
|
// connect to robot and setup ROS subscription
|
||||||
|
|||||||
@@ -24,7 +24,7 @@ ScoutROSMessenger::ScoutROSMessenger(ScoutBase *scout, ros::NodeHandle *nh)
|
|||||||
|
|
||||||
void ScoutROSMessenger::SetupSubscription() {
|
void ScoutROSMessenger::SetupSubscription() {
|
||||||
// odometry publisher
|
// 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_ =
|
status_publisher_ =
|
||||||
nh_->advertise<scout_msgs::ScoutStatus>("/scout_status", 10);
|
nh_->advertise<scout_msgs::ScoutStatus>("/scout_status", 10);
|
||||||
|
|
||||||
@@ -239,7 +239,7 @@ void ScoutROSMessenger::PublishOdometryToROS(double linear, double angular,
|
|||||||
// publish odometry and tf messages
|
// publish odometry and tf messages
|
||||||
nav_msgs::Odometry odom_msg;
|
nav_msgs::Odometry odom_msg;
|
||||||
odom_msg.header.stamp = current_time_;
|
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.child_frame_id = base_frame_;
|
||||||
|
|
||||||
odom_msg.pose.pose.position.x = position_x_;
|
odom_msg.pose.pose.position.x = position_x_;
|
||||||
|
|||||||
Reference in New Issue
Block a user