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

Added some messages and Fix a bug from PathMsg #10

Open
wants to merge 5 commits into
base: master
Choose a base branch
from
Open
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
41 changes: 41 additions & 0 deletions actionlib_msgs/GoalIDMsg.cs
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
using ROSBridgeLib.std_msgs;
using SimpleJSON;

namespace ROSBridgeLib
{
namespace actionlib_msgs
{
public class GoalIDMsg : ROSBridgeMsg
{
private TimeMsg time;
private string id;

public GoalIDMsg(JSONNode msg)
{
time = new TimeMsg(msg["stamp"]);
id = msg["id"].ToString();
}

public GoalIDMsg(TimeMsg _time, string _id)
{
time = _time;
id = _id;
}

public static string GetMessageType()
{
return "actionlib_msgs/GoalID";
}

public override string ToString()
{
return "actionlib_msgs/GoalID [ stamp: " + time.ToString() + "id: " + id + "}";
}

public override string ToYAMLString()
{
return "{\"stamp\": " + time.ToYAMLString() + ", \"id\": " + id + "}";
}
}
}
}
49 changes: 49 additions & 0 deletions actionlib_msgs/GoalStatusMsg.cs
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
using ROSBridgeLib.std_msgs;
using ROSBridgeLib.actionlib_msgs;
using SimpleJSON;

namespace ROSBridgeLib
{
namespace actionlib_msgs
{
public class GoalStatusMsg : ROSBridgeMsg
{
private GoalIDMsg goal_id;
private int status;
private string text;
public GoalStatusMsg(JSONNode msg)
{
goal_id = new GoalIDMsg(msg["goal_id"]);
status = int.Parse(msg["status"]);
text = msg["text"];
}

public GoalStatusMsg(GoalIDMsg _goal_id, int _status, string _text)
{
goal_id = _goal_id;
status = _status;
text = _text;
}

public static string GetMessageType()
{
return "actionlib_msgs/GoalStatus";
}

public override string ToString()
{
return "actionlib_msgs/GoalStatus [goal_id=" + goal_id.ToString() + ", status=" + status.ToString() + ", text=" + text;
}

public override string ToYAMLString()
{
return "{\"goal_id\": " + goal_id.ToYAMLString() + ", \"status\": " + status.ToString() + ", \"text\": " + text + "}";
}

public StatusType GetStatus()
{
return (StatusType)status;
}
}
}
}
24 changes: 24 additions & 0 deletions actionlib_msgs/GoalStatusType.cs
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
namespace ROSBridgeLib
{
namespace actionlib_msgs
{
public enum StatusType
{
PENDING, // The goal has yet to be processed by the action server.
ACTIVE, // The goal is currently being processed by the action server
PREEMPTED, // The goal received a cancel request after it started executing
// and has since completed its execution (Terminal State)
SUCCEEDED, // The goal was achieved successfully by the action server (Terminal State)
REJECTED, // The goal was aborted during execution by the action server due to some failure (Terminal State)
PREEMPTING, // The goal received a cancel request after it started executing
// and has not yet completed execution
RECALLING, // The goal received a cancel request before it started executing,
// but the action server has not yet confirmed that the goal is canceled
RECALLED, // The goal received a cancel request before it started executing
// and was successfully cancelled (Terminal State)
LOST // An action client can determine that a goal is LOST. This should not be
// sent over the wire by an action server
}

}
}
4 changes: 4 additions & 0 deletions geometry_msgs/PointMsg.cs
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,10 @@ public float GetY() {
public float GetZ() {
return _z;
}

public Vector3 GetVector3() {
return new Vector3(_x, _y, _z);
}

public override string ToString() {
return "geometry_msgs/Point [x=" + _x + ", y=" + _y + ", z=" + _z + "]";
Expand Down
4 changes: 2 additions & 2 deletions geometry_msgs/PoseMsg.cs
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
namespace ROSBridgeLib {
namespace geometry_msgs {
public class PoseMsg : ROSBridgeMsg {
public PointMsg _position;
public QuaternionMsg _orientation;
private PointMsg _position;
private QuaternionMsg _orientation;

public PoseMsg(JSONNode msg) {
_position = new PointMsg(msg["position"]);
Expand Down
2 changes: 1 addition & 1 deletion geometry_msgs/PoseWithCovarianceMsg.cs
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
namespace ROSBridgeLib {
namespace geometry_msgs {
public class PoseWithCovarianceMsg : ROSBridgeMsg {
public PoseMsg _pose;
private PoseMsg _pose;
private double[] _covariance = new double[36] {0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
Expand Down
50 changes: 50 additions & 0 deletions geometry_msgs/PoseWithCovarianceStampedMsg.cs
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
using ROSBridgeLib.geometry_msgs;
using ROSBridgeLib.std_msgs;

using SimpleJSON;

namespace ROSBridgeLib
{
namespace geometry_msgs {
class PoseWithCovarianceStampedMsg : ROSBridgeMsg{
private HeaderMsg header;
private PoseWithCovarianceMsg pose;

public PoseWithCovarianceStampedMsg(JSONNode msg)
{
header = new HeaderMsg(msg["header"]);
pose = new PoseWithCovarianceMsg(msg["pose"]);
}

public PoseWithCovarianceStampedMsg(HeaderMsg _header, PoseWithCovarianceMsg _pose)
{
header = _header;
pose = _pose;
}

public static string GetMessageType()
{
return "geometry_msgs/PoseWithCovarianceStamped";
}

public override string ToString()
{
return "geometry_msgs/PoseWithCovarianceStamped [header=" + header.ToString() + ", pose=" + pose.ToString() + "]";
}

public override string ToYAMLString()
{
return "{\"header\": " + header.ToYAMLString() + ", \"pose\": " + pose.ToYAMLString() + "}";
}

public PointMsg GetPosition()
{
return pose.GetPose().GetPosition();
}
public QuaternionMsg GetRotation()
{
return pose.GetPose().GetOrientation();
}
}
}
}
6 changes: 5 additions & 1 deletion geometry_msgs/QuaternionMsg.cs
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
using System.Collections;
using System.Text;
using SimpleJSON;

using UnityEngine;
/**
* Define a geometry_msgs quaternion message. This has been hand-crafted from the corresponding
* geometry_msgs message file.
Expand Down Expand Up @@ -47,6 +47,10 @@ public float GetZ() {
public float GetW() {
return _w;
}

public Quaternion GetQuaternion() {
return new Quaternion(_x, _y, _z, _w);
}

public override string ToString() {
return "geometry_msgs/Quaternion [x=" + _x + ", y=" + _y + ", z=" + _z + ", w=" + _w + "]";
Expand Down
59 changes: 59 additions & 0 deletions move_base_msgs/MoveBaseActionGoalMsg.cs
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
using ROSBridgeLib.std_msgs;
using ROSBridgeLib.actionlib_msgs;
using ROSBridgeLib.geometry_msgs;
using SimpleJSON;

namespace ROSBridgeLib
{
namespace move_base_msgs
{
public class MoveBaseActionGoalMsg : ROSBridgeMsg
{
private HeaderMsg header;
private GoalIDMsg goal_id;
private MoveBaseGoalMsg goal;
public MoveBaseActionGoalMsg(JSONNode msg)
{
header = new HeaderMsg(msg["header"]);
goal_id = new GoalIDMsg(msg["goal_id"]);
goal = new MoveBaseGoalMsg(msg["goal"]);
}

public MoveBaseActionGoalMsg(HeaderMsg _header, GoalIDMsg _goal_id, MoveBaseGoalMsg _goal)
{
header = _header;
goal_id = _goal_id;
goal = _goal;
}

public static string GetMessageType()
{
return "move_base_msgs/MoveBaseActionGoal";
}

public override string ToString()
{
return "move_base_msgs/MoveBaseActionGoal [header=" + header.ToString() +
", goal_id=" + goal_id.ToString() +
", goal=" + goal.ToString();
}

public override string ToYAMLString()
{
return "{\"header\": " + header.ToYAMLString() +
"\"goal_id\": " + goal_id.ToYAMLString() +
"\"goal\": " + goal.ToYAMLString() + "}";
}

public MoveBaseGoalMsg GetGoal()
{
return goal;
}

public PoseStampedMsg GetGoalPose()
{
return goal.GetTargetPose();
}
}
}
}
45 changes: 45 additions & 0 deletions move_base_msgs/MoveBaseGoalMsg.cs
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
using ROSBridgeLib.std_msgs;
using ROSBridgeLib.geometry_msgs;
using SimpleJSON;

namespace ROSBridgeLib
{
namespace move_base_msgs
{
public class MoveBaseGoalMsg : ROSBridgeMsg
{
private PoseStampedMsg target_pose;
public MoveBaseGoalMsg(JSONNode msg)
{
target_pose = new PoseStampedMsg(msg["target_pose"]);
}

public MoveBaseGoalMsg(PoseStampedMsg _target_pose)
{
target_pose = _target_pose;
}

public static string GetMessageType()
{
return "move_base_msgs/MoveBaseGoal";
}

public override string ToString()
{
return "move_base_msgs/MoveBaseGoal [target_pose=" + target_pose.ToString();
}


public override string ToYAMLString()
{
return "{\"target_pose\":" + target_pose.ToYAMLString() + "}";
}

public PoseStampedMsg GetTargetPose()
{
return target_pose;
}

}
}
}
43 changes: 43 additions & 0 deletions move_base_msgs/MoveBaseResultMsg.cs
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
using ROSBridgeLib.std_msgs;
using ROSBridgeLib.geometry_msgs;
using SimpleJSON;

namespace ROSBridgeLib
{
namespace move_base_msgs
{
public class MoveBaseResultMsg : ROSBridgeMsg
{
private string res;
public MoveBaseResultMsg(JSONNode msg)
{
res = msg.ToString();
}

public MoveBaseResultMsg(string _res)
{
res = _res;
}

public static string GetMessageType()
{
return "move_base_msgs/MoveBaseResult";
}

public override string ToString()
{
return "move_base_msgs/MoveBaseResult [" + res + "]";
}

public override string ToYAMLString()
{
return "{" + res + "}";
}

public string GetResult()
{
return res;
}
}
}
}
Loading