mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 19:25:01 +08:00
removed scout_sdk, replace with wrp_sdk
This commit is contained in:
@@ -5,10 +5,10 @@
|
||||
#include <tf/transform_broadcaster.h>
|
||||
#include <nav_msgs/Odometry.h>
|
||||
|
||||
#include "scout_sdk/scout_base.hpp"
|
||||
#include "wrp_sdk/platforms/scout/scout_base.hpp"
|
||||
#include "scout_base/scout_messenger.hpp"
|
||||
|
||||
using namespace wescore;
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
|
||||
@@ -5,10 +5,10 @@
|
||||
#include <tf/transform_broadcaster.h>
|
||||
#include <nav_msgs/Odometry.h>
|
||||
|
||||
#include "scout_sdk/scout_base.hpp"
|
||||
#include "wrp_sdk/platforms/scout/scout_base.hpp"
|
||||
#include "scout_base/scout_messenger.hpp"
|
||||
|
||||
using namespace wescore;
|
||||
using namespace westonrobot;
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
|
||||
@@ -13,7 +13,7 @@
|
||||
|
||||
#include "scout_msgs/ScoutStatus.h"
|
||||
|
||||
namespace wescore
|
||||
namespace westonrobot
|
||||
{
|
||||
ScoutROSMessenger::ScoutROSMessenger(ros::NodeHandle *nh) : scout_(nullptr), nh_(nh)
|
||||
{
|
||||
@@ -259,4 +259,4 @@ void ScoutROSMessenger::PublishOdometryToROS(double linear, double angular, doub
|
||||
|
||||
odom_publisher_.publish(odom_msg);
|
||||
}
|
||||
} // namespace wescore
|
||||
} // namespace westonrobot
|
||||
Reference in New Issue
Block a user