diff --git a/NOTE.md b/NOTE.md new file mode 100644 index 0000000..ed4c858 --- /dev/null +++ b/NOTE.md @@ -0,0 +1,3 @@ +``` +$ rostopic pub -1 /scout_motor_fl_controller/command std_msgs/Float64 "data: 0.5" +``` \ No newline at end of file diff --git a/scout_description/launch/scout_v2_stock.launch b/scout_description/launch/scout_v2_stock.launch index 37d50b5..0560131 100644 --- a/scout_description/launch/scout_v2_stock.launch +++ b/scout_description/launch/scout_v2_stock.launch @@ -1,5 +1,10 @@ - - + + + + diff --git a/scout_description/urdf/scout_v2.gazebo b/scout_description/urdf/scout_v2.gazebo index 522a2a7..e35d56c 100644 --- a/scout_description/urdf/scout_v2.gazebo +++ b/scout_description/urdf/scout_v2.gazebo @@ -16,7 +16,7 @@ - + $(arg robot_namespace) diff --git a/scout_description/urdf/scout_v2.xacro b/scout_description/urdf/scout_v2.xacro index e0ba235..ca55b32 100644 --- a/scout_description/urdf/scout_v2.xacro +++ b/scout_description/urdf/scout_v2.xacro @@ -3,6 +3,7 @@ + diff --git a/scout_gazebo_sim/CMakeLists.txt b/scout_gazebo_sim/CMakeLists.txt index 82c5242..ae3efa9 100644 --- a/scout_gazebo_sim/CMakeLists.txt +++ b/scout_gazebo_sim/CMakeLists.txt @@ -7,11 +7,9 @@ find_package(catkin REQUIRED COMPONENTS roslaunch roslint roscpp - sensor_msgs std_msgs + sensor_msgs geometry_msgs - scout_msgs - scout_sdk tf2 tf2_ros ) diff --git a/scout_gazebo_sim/include/scout_gazebo/scout_skid_steer.hpp b/scout_gazebo_sim/include/scout_gazebo/scout_skid_steer.hpp index 21d9e47..5d64b82 100644 --- a/scout_gazebo_sim/include/scout_gazebo/scout_skid_steer.hpp +++ b/scout_gazebo_sim/include/scout_gazebo/scout_skid_steer.hpp @@ -10,17 +10,39 @@ #ifndef SCOUT_SKID_STEER_HPP #define SCOUT_SKID_STEER_HPP -#include - +#include #include +#include + namespace wescore { class ScoutSkidSteer { public: - ScoutSkidSteer(std::string robot_name); + ScoutSkidSteer(ros::NodeHandle *nh, std::string robot_name = ""); + + void SetupSubscription(); private: - std::string robot_name; + std::string robot_name_; + std::string motor_fr_topic_; + std::string motor_fl_topic_; + std::string motor_rl_topic_; + std::string motor_rr_topic_; + std::string cmd_topic_; + + const double SCOUT_WHEELBASE = 0.498; + const double SCOUT_WHEEL_RADIUS = 0.16459; + + ros::NodeHandle *nh_; + + ros::Publisher motor_fr_pub_; + ros::Publisher motor_fl_pub_; + ros::Publisher motor_rl_pub_; + ros::Publisher motor_rr_pub_; + + ros::Subscriber cmd_sub_; + + void TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg); }; } // namespace wescore diff --git a/scout_gazebo_sim/launch/scout_empty_world.launch b/scout_gazebo_sim/launch/scout_empty_world.launch index b8f2368..1467714 100644 --- a/scout_gazebo_sim/launch/scout_empty_world.launch +++ b/scout_gazebo_sim/launch/scout_empty_world.launch @@ -25,6 +25,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI --> + @@ -37,7 +38,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI - + diff --git a/scout_gazebo_sim/launch/spawn_scout_v2.launch b/scout_gazebo_sim/launch/spawn_scout_v2.launch index efee5cf..3595e78 100644 --- a/scout_gazebo_sim/launch/spawn_scout_v2.launch +++ b/scout_gazebo_sim/launch/spawn_scout_v2.launch @@ -5,6 +5,8 @@ + + @@ -12,7 +14,9 @@ - + + + + -model 'scout$(arg robot_namespace)'" /> - + - - - + + + + + \ No newline at end of file diff --git a/scout_gazebo_sim/src/scout_skid_steer.cpp b/scout_gazebo_sim/src/scout_skid_steer.cpp index b63fb90..137f11c 100644 --- a/scout_gazebo_sim/src/scout_skid_steer.cpp +++ b/scout_gazebo_sim/src/scout_skid_steer.cpp @@ -9,6 +9,52 @@ #include "scout_gazebo/scout_skid_steer.hpp" +#include +#include + namespace wescore { - -} \ No newline at end of file +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"; + motor_fl_topic_ = robot_name_ + "/scout_motor_fl_controller/command"; + motor_rl_topic_ = robot_name_ + "/scout_motor_rl_controller/command"; + motor_rr_topic_ = robot_name_ + "/scout_motor_rr_controller/command"; + cmd_topic_ = robot_name_ + "/cmd_vel"; +} + +void ScoutSkidSteer::SetupSubscription() { + // command subscriber + cmd_sub_ = nh_->subscribe( + cmd_topic_, 5, &ScoutSkidSteer::TwistCmdCallback, this); + + // motor command publisher + motor_fr_pub_ = nh_->advertise(motor_fr_topic_, 50); + motor_fl_pub_ = nh_->advertise(motor_fl_topic_, 50); + motor_rl_pub_ = nh_->advertise(motor_rl_topic_, 50); + motor_rr_pub_ = nh_->advertise(motor_rr_topic_, 50); +} + +void ScoutSkidSteer::TwistCmdCallback( + const geometry_msgs::Twist::ConstPtr &msg) { + std_msgs::Float64 motor_cmd[4]; + + double driving_vel = msg->linear.x; + double steering_vel = msg->angular.z; + + double left_side_velocity = + (driving_vel - steering_vel * SCOUT_WHEELBASE) / SCOUT_WHEEL_RADIUS; + double right_side_velocity = + (driving_vel + steering_vel * SCOUT_WHEELBASE) / SCOUT_WHEEL_RADIUS; + + motor_cmd[0].data = right_side_velocity; + motor_cmd[1].data = -left_side_velocity; + motor_cmd[2].data = -left_side_velocity; + motor_cmd[3].data = right_side_velocity; + + motor_fr_pub_.publish(motor_cmd[0]); + motor_fl_pub_.publish(motor_cmd[1]); + motor_rl_pub_.publish(motor_cmd[2]); + motor_rr_pub_.publish(motor_cmd[3]); +} + +} // namespace wescore \ No newline at end of file diff --git a/scout_gazebo_sim/src/scout_skid_steer_controller.cpp b/scout_gazebo_sim/src/scout_skid_steer_controller.cpp index d6c33a4..1a704b1 100644 --- a/scout_gazebo_sim/src/scout_skid_steer_controller.cpp +++ b/scout_gazebo_sim/src/scout_skid_steer_controller.cpp @@ -1,52 +1,64 @@ -#include - +#include #include #include #include -#include + +#include #include "scout_gazebo/scout_skid_steer.hpp" using namespace wescore; -int main(int argc, char **argv) -{ - // setup ROS node - ros::init(argc, argv, "scout_odom"); - ros::NodeHandle node(""), private_node("~"); +int main(int argc, char **argv) { + // setup ROS node + ros::init(argc, argv, "scout_odom"); + ros::NodeHandle node(""), private_node("~"); - // // instantiate a robot object - // ScoutBase robot; - // ScoutROSMessenger messenger(&robot, &node); + // fetch parameters + std::string robot_namespace; + private_node.param("robot_namespace", robot_namespace, + std::string("scout_default")); - // // fetch parameters before connecting to robot - // std::string port_name; - // private_node.param("port_name", port_name, std::string("can0")); - // private_node.param("odom_frame", messenger.odom_frame_, std::string("odom")); - // private_node.param("base_frame", messenger.base_frame_, std::string("base_link")); - // private_node.param("simulated_robot", messenger.simulated_robot_, false); + ROS_INFO("Namespace: %s", robot_namespace.c_str()); - // // connect to robot and setup ROS subscription - // if (port_name.find("can") != std::string::npos) - // { - // robot.Connect(port_name); - // ROS_INFO("Using CAN bus to talk with the robot"); - // } - // else - // { - // robot.Connect(port_name, 115200); - // ROS_INFO("Using UART to talk with the robot"); - // } - // messenger.SetupSubscription(); + ScoutSkidSteer skid_steer_controller(&node, robot_namespace); + skid_steer_controller.SetupSubscription(); - // // publish robot state at 20Hz while listening to twist commands - // ros::Rate rate_20hz(20); // 20Hz - // while (true) - // { - // messenger.PublishStateToROS(); - // ros::spinOnce(); - // rate_20hz.sleep(); - // } + ros::spin(); - return 0; + // // instantiate a robot object + // ScoutBase robot; + // ScoutROSMessenger messenger(&robot, &node); + + // // fetch parameters before connecting to robot + // std::string port_name; + // private_node.param("port_name", port_name, + // std::string("can0")); private_node.param("odom_frame", + // messenger.odom_frame_, std::string("odom")); + // private_node.param("base_frame", messenger.base_frame_, + // std::string("base_link")); private_node.param("simulated_robot", + // messenger.simulated_robot_, false); + + // // connect to robot and setup ROS subscription + // if (port_name.find("can") != std::string::npos) + // { + // robot.Connect(port_name); + // ROS_INFO("Using CAN bus to talk with the robot"); + // } + // else + // { + // robot.Connect(port_name, 115200); + // ROS_INFO("Using UART to talk with the robot"); + // } + // messenger.SetupSubscription(); + + // publish robot state at 20Hz while listening to twist commands + // ros::Rate rate_20hz(20); // 20Hz + // while (true) { + // messenger.PublishStateToROS(); + // ros::spinOnce(); + // rate_20hz.sleep(); + // } + + return 0; } \ No newline at end of file