removed scout_sdk, replace with wrp_sdk

This commit is contained in:
Tan Pin Da
2020-08-21 15:17:41 +08:00
parent f73a2e2f59
commit f73e8c0ddf
529 changed files with 25 additions and 115711 deletions

View File

@@ -15,7 +15,7 @@
#include <string>
namespace wescore {
namespace westonrobot {
class ScoutSkidSteer {
public:
ScoutSkidSteer(ros::NodeHandle *nh, std::string robot_name = "");
@@ -44,6 +44,6 @@ class ScoutSkidSteer {
void TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg);
};
} // namespace wescore
} // namespace westonrobot
#endif /* SCOUT_SKID_STEER_HPP */

View File

@@ -12,7 +12,7 @@
#include <geometry_msgs/Twist.h>
#include <std_msgs/Float64.h>
namespace wescore {
namespace westonrobot {
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";
@@ -57,4 +57,4 @@ void ScoutSkidSteer::TwistCmdCallback(
motor_rr_pub_.publish(motor_cmd[3]);
}
} // namespace wescore
} // namespace westonrobot

View File

@@ -7,7 +7,7 @@
#include "scout_gazebo/scout_skid_steer.hpp"
using namespace wescore;
using namespace westonrobot;
int main(int argc, char **argv) {
// setup ROS node