Skip to content

Commit

Permalink
format
Browse files Browse the repository at this point in the history
  • Loading branch information
neuenfeldttj committed Apr 18, 2024
1 parent f261b3f commit c9accdc
Show file tree
Hide file tree
Showing 7 changed files with 25 additions and 23 deletions.
19 changes: 11 additions & 8 deletions scripts/debug_click_ik.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,15 @@
import actionlib
import sys


def click_ik_client():
# Creates the SimpleActionClient, passing the type of the action
client = actionlib.SimpleActionClient('do_click_ik', ClickIkAction)
print('created click ik client')
client = actionlib.SimpleActionClient("do_click_ik", ClickIkAction)
print("created click ik client")
# Waits until the action server has started up and started
# listening for goals.
client.wait_for_server()
print('Found server')
print("Found server")
# Creates a goal to send to the action server.
goal = ClickIkGoal()
# Sends the goal to the action server.
Expand All @@ -23,15 +24,17 @@ def click_ik_client():
result = client.get_result()
return result


def feedback(msg):
print(msg)


if __name__ == "__main__":
try:
# Initializes a rospy node so that the SimpleActionClient can
# publish and subscribe over ROS.
rospy.init_node('debug_click_ik')
# Initializes a rospy node so that the SimpleActionClient can
# publish and subscribe over ROS.
rospy.init_node("debug_click_ik")
result = click_ik_client()
print('result: ', result)
print("result: ", result)
except rospy.ROSInterruptException:
print("program interrupted before completion", file=sys.stderr)
print("program interrupted before completion", file=sys.stderr)
2 changes: 1 addition & 1 deletion src/perception/click_ik/click_ik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ namespace mrover {
}

geometry_msgs::Pose pose;

double offset = 0.1; // make sure we don't collide by moving back a little from the target
pose.position.x = target_point.value().x - offset;
pose.position.y = target_point.value().y;
Expand Down
6 changes: 3 additions & 3 deletions src/perception/click_ik/click_ik.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,15 @@ namespace mrover {
IK message;
ros::Timer timer;

const Point* mPoints{};
Point const* mPoints{};
std::size_t mNumPoints{};
std::size_t mPointCloudWidth{};
std::size_t mPointCloudHeight{};

tf2_ros::Buffer mTfBuffer{};
tf2_ros::TransformListener mTfListener{mTfBuffer};
tf2_ros::TransformBroadcaster mTfBroadcaster;

public:
ClickIkNodelet() = default;

Expand All @@ -35,7 +35,7 @@ namespace mrover {

void startClickIk();
void cancelClickIk();

//Taken line for line from percep object detection code
auto spiralSearchInImg(size_t xCenter, size_t yCenter) -> std::optional<Point>;
};
Expand Down
11 changes: 4 additions & 7 deletions src/perception/click_ik/pch.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,8 @@
#include <string>
#include <type_traits>
#include <unordered_map>
#include <limits>
#include <optional>

#include <actionlib/server/simple_action_server.h>
#include <dynamic_reconfigure/server.h>
#include <nodelet/loader.h>
#include <nodelet/nodelet.h>
Expand All @@ -24,15 +23,13 @@
#include <std_srvs/SetBool.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
#include <actionlib/server/simple_action_server.h>

#include <lie.hpp>
#include <loop_profiler.hpp>
#include <point.hpp>
#include <lie.hpp>


#include "mrover/ClickIkGoal.h"
#include "../teleoperation/arm_controller/arm_controller.hpp"
#include "mrover/ClickIkAction.h"
#include "mrover/ClickIkGoal.h"
#include "mrover/IK.h"
#include "../teleoperation/arm_controller/arm_controller.hpp"

2 changes: 1 addition & 1 deletion src/simulator/simulator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -422,7 +422,7 @@ namespace mrover {
template<typename F, typename N, typename V>
auto forEachWithMotor(N const& names, V const& values, F&& function) -> void {
if (auto it = mUrdfs.find("rover"); it != mUrdfs.end()) {
URDF & rover = it->second;
URDF& rover = it->second;

for (auto const& combined: boost::combine(names, values)) {
std::string const& name = boost::get<0>(combined);
Expand Down
2 changes: 1 addition & 1 deletion src/simulator/simulator.physics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ namespace mrover {
}
// check if arm motor commands have expired
// TODO(quintin): fix hard-coded names?
for (auto const& name : {"arm_a_link", "arm_b_link", "arm_c_link", "arm_d_link", "arm_e_link"}) {
for (auto const& name: {"arm_a_link", "arm_b_link", "arm_c_link", "arm_d_link", "arm_e_link"}) {
bool expired = std::chrono::duration_cast<std::chrono::milliseconds>(Clock::now() - rover.linkNameToMeta.at(name).lastUpdate).count() > 20;
if (expired) {
int linkIndex = rover.linkNameToMeta.at(name).index;
Expand Down
6 changes: 4 additions & 2 deletions src/teleoperation/backend/consumers.py
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ def connect(self):
self.cmd_vel = rospy.Subscriber("/cmd_vel", Twist, self.cmd_vel_callback)

# Action clients
self.click_ik_client = actionlib.SimpleActionClient('do_click_ik', ClickIkAction)
self.click_ik_client = actionlib.SimpleActionClient("do_click_ik", ClickIkAction)

# Services
self.laser_service = rospy.ServiceProxy("enable_arm_laser", SetBool)
Expand Down Expand Up @@ -805,13 +805,15 @@ def flight_attitude_listener(self):
self.send(text_data=json.dumps({"type": "flight_attitude", "pitch": pitch, "roll": roll}))

rate.sleep()

def start_click_ik(self, msg) -> None:
goal = ClickIkGoal()
goal.pointInImageX = msg["data"]["x"]
goal.pointInImageY = msg["data"]["y"]

def feedback_cb(feedback: ClickIkFeedback) -> None:
self.send(text_data=json.dumps({"type": "click_ik_feedback", "distance": feedback.distance}))

self.click_ik_client.send_goal(goal, feedback_cb=feedback_cb)

def cancel_click_ik(self, msg) -> None:
Expand Down

0 comments on commit c9accdc

Please sign in to comment.