mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
removed scout_sdk, replace with wrp_sdk
This commit is contained in:
@@ -12,7 +12,7 @@
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
namespace wescore
|
||||
namespace westonrobot
|
||||
{
|
||||
struct ScoutSimParams
|
||||
{
|
||||
@@ -30,7 +30,7 @@ struct ScoutSimParams
|
||||
static constexpr double max_angular_speed = 0.7853; // in rad/s
|
||||
static constexpr double max_speed_cmd = 10.0; // in rad/s
|
||||
};
|
||||
} // namespace wescore
|
||||
} // namespace westonrobot
|
||||
|
||||
|
||||
#endif /* SCOUT_SIM_PARAMS_HPP */
|
||||
|
||||
@@ -18,7 +18,7 @@
|
||||
|
||||
#include "scout_base/scout_messenger.hpp"
|
||||
|
||||
namespace wescore
|
||||
namespace westonrobot
|
||||
{
|
||||
class ScoutWebotsInterface
|
||||
{
|
||||
@@ -36,6 +36,6 @@ private:
|
||||
std::string robot_name_ = "agilex_scout";
|
||||
const std::vector<std::string> motor_names_{"motor_fr", "motor_fl", "motor_rl", "motor_rr"};
|
||||
};
|
||||
} // namespace wescore
|
||||
} // namespace westonrobot
|
||||
|
||||
#endif /* SCOUT_WEBOTS_INTERFACE_HPP */
|
||||
|
||||
@@ -20,7 +20,7 @@
|
||||
|
||||
#include "scout_webots_sim/scout_sim_params.hpp"
|
||||
|
||||
namespace wescore
|
||||
namespace westonrobot
|
||||
{
|
||||
ScoutWebotsInterface::ScoutWebotsInterface(ros::NodeHandle *nh, ScoutROSMessenger *msger, uint32_t time_step)
|
||||
: nh_(nh), messenger_(msger), time_step_(time_step)
|
||||
@@ -126,4 +126,4 @@ void ScoutWebotsInterface::UpdateSimState()
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace wescore
|
||||
} // namespace westonrobot
|
||||
@@ -19,7 +19,7 @@
|
||||
|
||||
#include "scout_webots_sim/scout_webots_interface.hpp"
|
||||
|
||||
using namespace wescore;
|
||||
using namespace westonrobot;
|
||||
|
||||
ros::ServiceClient timeStepClient;
|
||||
webots_ros::set_int timeStepSrv;
|
||||
|
||||
Reference in New Issue
Block a user