updated pkg to use wrp_sdk, removed scout_webots_sim

This commit is contained in:
Ruixiang Du
2020-07-28 18:47:18 +08:00
parent 8658e1cba3
commit 4af0482819
534 changed files with 12 additions and 117058 deletions

View File

@@ -15,7 +15,7 @@ find_package(catkin REQUIRED COMPONENTS
std_msgs
geometry_msgs
scout_msgs
scout_sdk
wrp_sdk
tf2
tf2_ros
)
@@ -29,7 +29,7 @@ find_package(catkin REQUIRED COMPONENTS
catkin_package(
INCLUDE_DIRS include
LIBRARIES scout_messenger
CATKIN_DEPENDS scout_msgs roscpp sensor_msgs scout_sdk
CATKIN_DEPENDS scout_msgs roscpp sensor_msgs
# DEPENDS Boost
)

View File

@@ -18,9 +18,9 @@
#include <tf2_ros/transform_broadcaster.h>
#include "scout_msgs/ScoutLightCmd.h"
#include "scout_sdk/scout_base.hpp"
#include "wrp_sdk/platforms/scout/scout_base.hpp"
namespace wescore
namespace westonrobot
{
class ScoutROSMessenger
{
@@ -68,6 +68,6 @@ private:
void LightCmdCallback(const scout_msgs::ScoutLightCmd::ConstPtr &msg);
void PublishOdometryToROS(double linear, double angular, double dt);
};
} // namespace wescore
} // namespace westonrobot
#endif /* SCOUT_MESSENGER_HPP */

View File

@@ -19,13 +19,13 @@
<build_depend>roslaunch</build_depend>
<build_depend>roslint</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>scout_sdk</build_depend>
<build_depend>wrp_sdk</build_depend>
<run_depend>controller_manager</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>scout_msgs</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>topic_tools</run_depend>
<run_depend>scout_sdk</run_depend>
<run_depend>wrp_sdk</run_depend>
<export></export>
</package>

View File

@@ -1,72 +0,0 @@
/*
* imu_broadcast_node.cpp
*
* Created on: Oct 02, 2019 19:09
* Description:
*
* Copyright (c) 2019 Ruixiang Du (rdu)
*/
#include <string>
#include <lcm/lcm-cpp.hpp>
#include "lcmtypes/wescore.hpp"
#include <ros/ros.h>
#include <sensor_msgs/Imu.h>
ros::Publisher imu_pub;
struct MessageBroadcaster
{
void IMULCMCallback(const lcm::ReceiveBuffer *rbuf, const std::string &chan, const wescore_lcm_msgs::IMU *msg)
{
static uint64_t count = 0;
// std::cout << "imu msg received" << std::endl;
sensor_msgs::Imu imu_msg;
imu_msg.header.frame_id = "imu_link";
imu_msg.header.stamp = ros::Time::now();
imu_msg.header.seq = count++;
imu_msg.angular_velocity.x = msg->angular_velocity.x;
imu_msg.angular_velocity.y = msg->angular_velocity.y;
imu_msg.angular_velocity.z = msg->angular_velocity.z;
imu_msg.linear_acceleration.x = msg->linear_acceleration.x;
imu_msg.linear_acceleration.y = msg->linear_acceleration.y;
imu_msg.linear_acceleration.z = msg->linear_acceleration.z;
for (int i = 0; i < 9; ++i)
{
imu_msg.orientation_covariance[i] = msg->orientation_covariance[i];
imu_msg.angular_velocity_covariance[i] = msg->angular_velocity_covariance[i];
imu_msg.linear_acceleration_covariance[i] = msg->linear_acceleration_covariance[i];
}
imu_pub.publish(imu_msg);
}
};
int main(int argc, char **argv)
{
// setup LCM
lcm::LCM lcm;
if (!lcm.good())
return 1;
MessageBroadcaster mb;
lcm.subscribe("sensor_hub_raw_imu", &MessageBroadcaster::IMULCMCallback, &mb);
// setup ROS node
ros::init(argc, argv, "imu_broadcast_node");
ros::NodeHandle nh;
imu_pub = nh.advertise<sensor_msgs::Imu>("imu", 1000);
ROS_INFO("Started broadcasting");
while (ros::ok())
{
lcm.handleTimeout(5);
}
return 0;
}

View File

@@ -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)
{

View File

@@ -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