Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Arm bridge for the simulator #580

Merged
merged 3 commits into from
Oct 12, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 4 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -241,12 +241,14 @@ else ()

add_cpp_interface_library_macro(moteus deps/moteus/lib/cpp/mjbots)

add_gazebo_plugin_macro(differential_drive_plugin_6w src/gazebo/differential_drive_6w.cpp src)
add_gazebo_plugin_macro(differential_drive_plugin_6w src/simulator/differential_drive_6w.cpp src)

add_gazebo_plugin_macro(kinect_plugin src/gazebo/gazebo_ros_openni_kinect.cpp src/gazebo)
add_gazebo_plugin_macro(kinect_plugin src/simulator/gazebo_ros_openni_kinect.cpp src/simulator)
target_link_libraries(kinect_plugin PRIVATE gazebo_ros_camera_utils DepthCameraPlugin Eigen3::Eigen)
set_target_properties(kinect_plugin PROPERTIES CXX_CLANG_TIDY "")

add_cpp_node_macro(sim_arm_bridge src/simulator/arm_bridge/*.cpp)

if (ZED_FOUND)
add_cpp_nodelet_macro(zed_nodelet src/perception/zed_wrapper/*.c* src/perception/zed_wrapper)
target_precompile_headers(zed_nodelet PRIVATE src/perception/zed_wrapper/pch.hpp)
Expand Down
30 changes: 30 additions & 0 deletions src/simulator/arm_bridge/sim_arm_bridge.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include "sim_arm_bridge.hpp"

#include <ros/init.h>
#include <ros/node_handle.h>
#include <sensor_msgs/JointState.h>

ros::Subscriber subscriber;

ros::Publisher jointStatePublisher;

constexpr std::string_view ARM_THROTTLE_CMD_TOPIC = "arm_throttle_cmd";
constexpr std::string_view ARM_VELOCITY_CMD_TOPIC = "arm_velocity_cmd";
constexpr std::string_view ARM_POSITION_CMD_TOPIC = "arm_position_cmd";

int main(int argc, char* argv[]) {
ros::init(argc, argv, "sim_arm_bridge");
ros::NodeHandle nh;

subscriber = nh.subscribe(std::string{ARM_POSITION_CMD_TOPIC}, 1, positionCallback);

ros::spin();
return EXIT_SUCCESS;
}

void positionCallback(mrover::Position const& positions) {
sensor_msgs::JointState jointState;
jointState.name = positions.names;
jointState.position.assign(positions.positions.begin(), positions.positions.end());
jointStatePublisher.publish(jointState);
}
5 changes: 5 additions & 0 deletions src/simulator/arm_bridge/sim_arm_bridge.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
#pragma once

#include <mrover/Position.h>

void positionCallback(mrover::Position const& positions);
Loading